robots_loader.py
Go to the documentation of this file.
1 import sys
2 import warnings
3 from os.path import dirname, exists, join
4 
5 import numpy as np
6 import pinocchio as pin
7 from pinocchio.robot_wrapper import RobotWrapper
8 
9 pin.switchToNumpyArray()
10 
11 
12 def _depr_msg(deprecated, key):
13  return "`%s` is deprecated. Please use `load('%s')`" % (deprecated, key)
14 
15 
16 def getModelPath(subpath, printmsg=False):
17  source = dirname(dirname(dirname(__file__))) # top level source directory
18  paths = [
19  join(dirname(dirname(dirname(source))), 'robots'), # function called from "make release" in build/ dir
20  join(dirname(source), 'robots'), # function called from a build/ dir inside top level source
21  join(source, 'robots') # function called from top level source dir
22  ]
23  try:
24  from .path import EXAMPLE_ROBOT_DATA_MODEL_DIR, EXAMPLE_ROBOT_DATA_SOURCE_DIR
25  paths.append(EXAMPLE_ROBOT_DATA_MODEL_DIR) # function called from installed project
26  paths.append(EXAMPLE_ROBOT_DATA_SOURCE_DIR) # function called from off-tree build dir
27  except ImportError:
28  pass
29  paths += [join(p, '../../../share/example-robot-data/robots') for p in sys.path]
30  for path in paths:
31  if exists(join(path, subpath.strip('/'))):
32  if printmsg:
33  print("using %s as modelPath" % path)
34  return path
35  raise IOError('%s not found' % subpath)
36 
37 
38 def readParamsFromSrdf(model, SRDF_PATH, verbose=False, has_rotor_parameters=True, referencePose='half_sitting'):
39  if has_rotor_parameters:
40  pin.loadRotorParameters(model, SRDF_PATH, verbose)
41  model.armature = np.multiply(model.rotorInertia.flat, np.square(model.rotorGearRatio.flat))
42  pin.loadReferenceConfigurations(model, SRDF_PATH, verbose)
43  q0 = pin.neutral(model)
44  if referencePose is not None:
45  q0 = model.referenceConfigurations[referencePose].copy()
46  return q0
47 
48 
49 class RobotLoader(object):
50  path = ''
51  urdf_filename = ''
52  srdf_filename = ''
53  urdf_subpath = 'robots'
54  srdf_subpath = 'srdf'
55  ref_posture = 'half_sitting'
56  has_rotor_parameters = False
57  free_flyer = False
58  verbose = False
59 
60  def __init__(self):
61  urdf_path = join(self.path, self.urdf_subpath, self.urdf_filename)
62  self.model_path = getModelPath(urdf_path, self.verbose)
63  self.urdf_path = join(self.model_path, urdf_path)
64  self.robot = RobotWrapper.BuildFromURDF(self.urdf_path, [join(self.model_path, '../..')],
65  pin.JointModelFreeFlyer() if self.free_flyer else None)
66 
67  if self.srdf_filename:
68  self.srdf_path = join(self.model_path, self.path, self.srdf_subpath, self.srdf_filename)
69  self.robot.q0 = readParamsFromSrdf(self.robot.model, self.srdf_path, self.verbose,
71  else:
72  self.srdf_path = None
73  self.robot.q0 = None
74 
75  if self.free_flyer:
77 
79  ub = self.robot.model.upperPositionLimit
80  ub[:7] = 1
81  self.robot.model.upperPositionLimit = ub
82  lb = self.robot.model.lowerPositionLimit
83  lb[:7] = -1
84  self.robot.model.lowerPositionLimit = lb
85 
86  @property
87  def q0(self):
88  warnings.warn("`q0` is deprecated. Please use `robot.q0`", FutureWarning, 2)
89  return self.robot.q0
90 
91 
93  path = 'anymal_b_simple_description'
94  urdf_filename = "anymal.urdf"
95  srdf_filename = "anymal.srdf"
96  ref_posture = "standing"
97  free_flyer = True
98 
99 
101  urdf_filename = "anymal-kinova.urdf"
102  srdf_filename = "anymal-kinova.srdf"
103  ref_posture = "standing_with_arm_up"
104 
105 
106 def loadANYmal(withArm=None):
107  if withArm:
108  warnings.warn(_depr_msg('loadANYmal(kinova)', 'anymal_kinova'), FutureWarning, 2)
109  loader = ANYmalKinovaLoader
110  else:
111  warnings.warn(_depr_msg('loadANYmal()', 'anymal'), FutureWarning, 2)
112  loader = ANYmalLoader
113  return loader().robot
114 
115 
117  path = 'talos_data'
118  urdf_filename = "talos_reduced.urdf"
119  srdf_filename = "talos.srdf"
120  free_flyer = True
121 
122 
124  urdf_filename = "talos_reduced_box.urdf"
125 
126 
128  urdf_filename = "talos_full_v2.urdf"
129 
130 
132  urdf_filename = "talos_full_v2_box.urdf"
133 
134 
136  urdf_filename = "talos_left_arm.urdf"
137  free_flyer = False
138 
139 
141  def __init__(self):
142  super(TalosLegsLoader, self).__init__()
143  legMaxId = 14
144  m1 = self.robot.model
145  m2 = pin.Model()
146  for j, M, name, parent, Y in zip(m1.joints, m1.jointPlacements, m1.names, m1.parents, m1.inertias):
147  if j.id < legMaxId:
148  jid = m2.addJoint(parent, getattr(pin, j.shortname())(), M, name)
149  upperPos = m2.upperPositionLimit
150  lowerPos = m2.lowerPositionLimit
151  effort = m2.effortLimit
152  upperPos[m2.joints[jid].idx_q:m2.joints[jid].idx_q + j.nq] = m1.upperPositionLimit[j.idx_q:j.idx_q +
153  j.nq]
154  lowerPos[m2.joints[jid].idx_q:m2.joints[jid].idx_q + j.nq] = m1.lowerPositionLimit[j.idx_q:j.idx_q +
155  j.nq]
156  effort[m2.joints[jid].idx_v:m2.joints[jid].idx_v + j.nv] = m1.effortLimit[j.idx_v:j.idx_v + j.nv]
157  m2.upperPositionLimit = upperPos
158  m2.lowerPositionLimit = lowerPos
159  m2.effortLimit = effort
160  assert jid == j.id
161  m2.appendBodyToJoint(jid, Y, pin.SE3.Identity())
162 
163  upperPos = m2.upperPositionLimit
164  upperPos[:7] = 1
165  m2.upperPositionLimit = upperPos
166  lowerPos = m2.lowerPositionLimit
167  lowerPos[:7] = -1
168  m2.lowerPositionLimit = lowerPos
169  effort = m2.effortLimit
170  effort[:6] = np.inf
171  m2.effortLimit = effort
172 
173  # q2 = self.robot.q0[:19]
174  for f in m1.frames:
175  if f.parent < legMaxId:
176  m2.addFrame(f)
177 
178  g2 = pin.GeometryModel()
179  for g in self.robot.visual_model.geometryObjects:
180  if g.parentJoint < 14:
181  g2.addGeometryObject(g)
182 
183  self.robot.model = m2
184  self.robot.data = m2.createData()
185  self.robot.visual_model = g2
186  # self.robot.q0=q2
187  self.robot.visual_data = pin.GeometryData(g2)
188 
189  # Load SRDF file
190  self.robot.q0 = readParamsFromSrdf(self.robot.model, self.srdf_path, self.verbose,
192 
193  assert (m2.armature[:6] == 0.).all()
194  # Add the free-flyer joint limits to the new model
196 
197 
198 def loadTalos(legs=False, arm=False, full=False, box=False):
199  if legs:
200  warnings.warn(_depr_msg('loadTalos(legs)', 'talos_legs'), FutureWarning, 2)
201  loader = TalosLegsLoader
202  elif arm:
203  warnings.warn(_depr_msg('loadTalos(arm)', 'talos_arm'), FutureWarning, 2)
204  loader = TalosArmLoader
205  elif full:
206  if box:
207  warnings.warn(_depr_msg('loadTalos(full, box)', 'talos_full_box'), FutureWarning, 2)
208  loader = TalosFullBoxLoader
209  else:
210  warnings.warn(_depr_msg('loadTalos(full)', 'talos_full'), FutureWarning, 2)
211  loader = TalosFullLoader
212  else:
213  if box:
214  warnings.warn(_depr_msg('loadTalos(box)', 'talos_box'), FutureWarning, 2)
215  loader = TalosBoxLoader
216  else:
217  warnings.warn(_depr_msg('loadTalos()', 'talos'), FutureWarning, 2)
218  loader = TalosLoader
219  return loader().robot
220 
221 
223  warnings.warn(_depr_msg('loadTalosLegs()', 'talos_legs'), FutureWarning, 2)
224  return loadTalos(legs=True)
225 
226 
228  warnings.warn(_depr_msg('loadTalosArm()', 'talos_arm'), FutureWarning, 2)
229  return loadTalos(arm=True)
230 
231 
233  path = "hyq_description"
234  urdf_filename = "hyq_no_sensors.urdf"
235  srdf_filename = "hyq.srdf"
236  ref_posture = "standing"
237  free_flyer = True
238 
239 
240 def loadHyQ():
241  warnings.warn(_depr_msg('loadHyQ()', 'hyq'), FutureWarning, 2)
242  return HyQLoader().robot
243 
244 
246  path = 'solo_description'
247  urdf_filename = "solo.urdf"
248  srdf_filename = "solo.srdf"
249  ref_posture = "standing"
250  free_flyer = True
251 
252 
254  urdf_filename = "solo12.urdf"
255 
256 
257 def loadSolo(solo=True):
258  warnings.warn(_depr_msg('loadSolo()', 'solo'), FutureWarning, 2)
259  loader = SoloLoader if solo else Solo12Loader
260  return loader().robot
261 
262 
264  path = "kinova_description"
265  urdf_filename = "kinova.urdf"
266  srdf_filename = "kinova.srdf"
267  ref_posture = "arm_up"
268 
269 
271  warnings.warn(_depr_msg('loadKinova()', 'kinova'), FutureWarning, 2)
272  return KinovaLoader().robot
273 
274 
276  path = "tiago_description"
277  urdf_filename = "tiago.urdf"
278 
279 
281  urdf_filename = "tiago_no_hand.urdf"
282 
283 
284 def loadTiago(hand=True):
285  if hand:
286  warnings.warn(_depr_msg('loadTiago()', 'tiago'), FutureWarning, 2)
287  loader = TiagoLoader
288  else:
289  warnings.warn(_depr_msg('loadTiago(hand=False)', 'tiago_no_hand'), FutureWarning, 2)
290  loader = TiagoNoHandLoader
291  return loader().robot
292 
293 
295  warnings.warn(_depr_msg('loadTiagoNoHand()', 'tiago_no_hand'), FutureWarning, 2)
296  return loadTiago(hand=False)
297 
298 
300  path = "icub_description"
301  urdf_filename = "icub.urdf"
302  srdf_filename = "icub.srdf"
303  free_flyer = True
304 
305 
307  urdf_filename = "icub_reduced.urdf"
308 
309 
310 def loadICub(reduced=True):
311  if reduced:
312  warnings.warn(_depr_msg('loadICub()', 'icub_reduced'), FutureWarning, 2)
313  loader = ICubReducedLoader
314  else:
315  warnings.warn(_depr_msg('loadICub(reduced=False)', 'icub'), FutureWarning, 2)
316  loader = ICubLoader
317  return loader().robot
318 
319 
321  path = "panda_description"
322  urdf_filename = "panda.urdf"
323  urdf_subpath = "urdf"
324 
325 
326 def loadPanda():
327  warnings.warn(_depr_msg('loadPanda()', 'panda'), FutureWarning, 2)
328  return PandaLoader().robot
329 
330 
332  path = "ur_description"
333  urdf_filename = "ur3_robot.urdf"
334  urdf_subpath = "urdf"
335  ref_posture = None
336 
337 
339  urdf_filename = "ur3_gripper.urdf"
340  srdf_filename = "ur3_gripper.srdf"
341 
342 
344  urdf_filename = "ur3_joint_limited_robot.urdf"
345 
346 
348  urdf_filename = "ur5_robot.urdf"
349  srdf_filename = "ur5.srdf"
350 
351 
353  urdf_filename = "ur5_gripper.urdf"
354  srdf_filename = "ur5_gripper.srdf"
355 
356 
358  urdf_filename = "ur5_joint_limited_robot.urdf"
359 
360 
362  urdf_filename = "ur10_robot.urdf"
363 
364 
366  urdf_filename = "ur10_joint_limited_robot.urdf"
367 
368 
369 def loadUR(robot=5, limited=False, gripper=False):
370  if robot == 3:
371  if limited:
372  warnings.warn(_depr_msg('loadUr(3, limited)', 'ur3_limited'), FutureWarning, 2)
373  loader = UR3LimitedLoader
374  elif gripper:
375  warnings.warn(_depr_msg('loadUr(3, gripper)', 'ur3_gripper'), FutureWarning, 2)
376  loader = UR3GripperLoader
377  else:
378  warnings.warn(_depr_msg('loadUr(3)', 'ur3'), FutureWarning, 2)
379  loader = UR3Loader
380  elif robot == 5:
381  if limited:
382  warnings.warn(_depr_msg('loadUr(limited)', 'ur5_limited'), FutureWarning, 2)
383  loader = UR5LimitedLoader
384  elif gripper:
385  warnings.warn(_depr_msg('loadUr(gripper)', 'ur5_gripper'), FutureWarning, 2)
386  loader = UR5GripperLoader
387  else:
388  warnings.warn(_depr_msg('loadUr()', 'ur5'), FutureWarning, 2)
389  loader = UR5Loader
390  elif robot == 10:
391  if limited:
392  warnings.warn(_depr_msg('loadUr(10, limited)', 'ur10_limited'), FutureWarning, 2)
393  loader = UR10LimitedLoader
394  else:
395  warnings.warn(_depr_msg('loadUr(10)', 'ur10'), FutureWarning, 2)
396  loader = UR10Loader
397  return loader().robot
398 
399 
401  path = "hector_description"
402  urdf_filename = "quadrotor_base.urdf"
403  free_flyer = True
404 
405 
407  warnings.warn(_depr_msg('loadHector()', 'hector'), FutureWarning, 2)
408  return HectorLoader().robot
409 
410 
412  path = "double_pendulum_description"
413  urdf_filename = "double_pendulum.urdf"
414  urdf_subpath = "urdf"
415 
416 
418  warnings.warn(_depr_msg('loadDoublePendulum()', 'double_pendulum'), FutureWarning, 2)
419  return DoublePendulumLoader().robot
420 
421 
423  path = "romeo_description"
424  urdf_filename = "romeo.urdf"
425  urdf_subpath = "urdf"
426  free_flyer = True
427 
428 
429 def loadRomeo():
430  warnings.warn(_depr_msg('loadRomeo()', 'romeo'), FutureWarning, 2)
431  return RomeoLoader().robot
432 
433 
435  path = 'simple_humanoid_description'
436  urdf_subpath = 'urdf'
437  urdf_filename = 'simple_humanoid.urdf'
438  srdf_filename = 'simple_humanoid.srdf'
439  free_flyer = True
440 
441 
443  urdf_filename = 'simple_humanoid_classical.urdf'
444  srdf_filename = 'simple_humanoid_classical.srdf'
445 
446 
448  path = "iris_description"
449  urdf_filename = "iris_simple.urdf"
450  free_flyer = True
451 
452 
453 def loadIris():
454  warnings.warn(_depr_msg('loadIris()', 'iris'), FutureWarning, 2)
455  return IrisLoader().robot
456 
457 
458 ROBOTS = {
459  'anymal': ANYmalLoader,
460  'anymal_kinova': ANYmalKinovaLoader,
461  'double_pendulum': DoublePendulumLoader,
462  'hector': HectorLoader,
463  'hyq': HyQLoader,
464  'icub': ICubLoader,
465  'icub_reduced': ICubReducedLoader,
466  'iris': IrisLoader,
467  'kinova': KinovaLoader,
468  'panda': PandaLoader,
469  'romeo': RomeoLoader,
470  'simple_humanoid': SimpleHumanoidLoader,
471  'simple_humanoid_classical': SimpleHumanoidClassicalLoader,
472  'solo': SoloLoader,
473  'solo12': Solo12Loader,
474  'talos': TalosLoader,
475  'talos_box': TalosBoxLoader,
476  'talos_arm': TalosArmLoader,
477  'talos_legs': TalosLegsLoader,
478  'talos_full': TalosFullLoader,
479  'talos_full_box': TalosFullBoxLoader,
480  'tiago': TiagoLoader,
481  'tiago_no_hand': TiagoNoHandLoader,
482  'ur3': UR5Loader,
483  'ur3_gripper': UR3GripperLoader,
484  'ur3_limited': UR3LimitedLoader,
485  'ur5': UR5Loader,
486  'ur5_gripper': UR5GripperLoader,
487  'ur5_limited': UR5LimitedLoader,
488  'ur10': UR10Loader,
489  'ur10_limited': UR10LimitedLoader,
490 }
491 
492 
493 def loader(name, display=False, rootNodeName=''):
494  """Load a robot by its name, and optionnaly display it in a viewer."""
495  if name not in ROBOTS:
496  robots = ", ".join(sorted(ROBOTS.keys()))
497  raise ValueError("Robot '%s' not found. Possible values are %s" % (name, robots))
498  inst = ROBOTS[name]()
499  if display:
500  if rootNodeName:
501  inst.robot.initViewer()
502  inst.robot.viz.loadViewerModel(rootNodeName=rootNodeName)
503  else:
504  inst.robot.initViewer(loadModel=True)
505  inst.robot.display(inst.robot.q0)
506  return inst
507 
508 
509 def load(name, display=False, rootNodeName=''):
510  """Load a robot by its name, and optionnaly display it in a viewer."""
511  return loader(name, display, rootNodeName).robot
512 
513 
514 def load_full(name, display=False, rootNodeName=''):
515  """Load a robot by its name, optionnaly display it in a viewer, and provide its q0 and paths."""
516  inst = loader(name, display, rootNodeName)
517  return inst.robot, inst.robot.q0, inst.urdf_path, inst.srdf_path
def load_full(name, display=False, rootNodeName='')
def _depr_msg(deprecated, key)
def readParamsFromSrdf(model, SRDF_PATH, verbose=False, has_rotor_parameters=True, referencePose='half_sitting')
def load(name, display=False, rootNodeName='')
def loadUR(robot=5, limited=False, gripper=False)
def getModelPath(subpath, printmsg=False)
def loadTalos(legs=False, arm=False, full=False, box=False)
def loader(name, display=False, rootNodeName='')
void copy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &origin, DataTpl< Scalar, Options, JointCollectionTpl > &dest, KinematicLevel kinematic_level)
Copy part of the data from origin to dest. Template parameter can be used to select at which differen...
Definition: copy.hpp:52


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04