robots_loader.py
Go to the documentation of this file.
1 import sys
2 from os.path import dirname, exists, join
3 
4 import numpy as np
5 import pinocchio as pin
6 from pinocchio.robot_wrapper import RobotWrapper
7 
8 pin.switchToNumpyArray()
9 
10 
11 def getModelPath(subpath, printmsg=False):
12  source = dirname(dirname(dirname(__file__))) # top level source directory
13  paths = [
14  join(
15  dirname(dirname(dirname(source))), "robots"
16  ), # function called from "make release" in build/ dir
17  join(
18  dirname(source), "robots"
19  ), # function called from a build/ dir inside top level source
20  join(source, "robots"), # function called from top level source dir
21  ]
22  try:
23  from .path import EXAMPLE_ROBOT_DATA_MODEL_DIR, EXAMPLE_ROBOT_DATA_SOURCE_DIR
24 
25  paths.append(
26  EXAMPLE_ROBOT_DATA_MODEL_DIR
27  ) # function called from installed project
28  paths.append(
29  EXAMPLE_ROBOT_DATA_SOURCE_DIR
30  ) # function called from off-tree build dir
31  except ImportError:
32  pass
33  paths += [join(p, "../../../share/example-robot-data/robots") for p in sys.path]
34  for path in paths:
35  if exists(join(path, subpath.strip("/"))):
36  if printmsg:
37  print("using %s as modelPath" % path)
38  return path
39  raise IOError("%s not found" % subpath)
40 
41 
43  model,
44  SRDF_PATH,
45  verbose=False,
46  has_rotor_parameters=True,
47  referencePose="half_sitting",
48 ):
49  if has_rotor_parameters:
50  pin.loadRotorParameters(model, SRDF_PATH, verbose)
51  model.armature = np.multiply(
52  model.rotorInertia.flat, np.square(model.rotorGearRatio.flat)
53  )
54  pin.loadReferenceConfigurations(model, SRDF_PATH, verbose)
55  q0 = pin.neutral(model)
56  if referencePose is not None:
57  q0 = model.referenceConfigurations[referencePose].copy()
58  q0 = pin.normalize(model, q0)
59  return q0
60 
61 
62 class RobotLoader(object):
63  path = ""
64  urdf_filename = ""
65  srdf_filename = ""
66  sdf_filename = ""
67  sdf_root_link_name = ""
68  sdf_parent_guidance = []
69  urdf_subpath = "robots"
70  srdf_subpath = "srdf"
71  sdf_subpath = ""
72  ref_posture = "half_sitting"
73  has_rotor_parameters = False
74  free_flyer = False
75  verbose = False
76  model_path = None
77 
78  def __init__(self):
79  if self.urdf_filename:
80  if self.sdf_filename:
81  raise AttributeError("Please choose between URDF *or* SDF")
82  df_path = join(self.path, self.urdf_subpath, self.urdf_filename)
83  builder = RobotWrapper.BuildFromURDF
84  if self.model_path is None:
85  self.model_path = getModelPath(df_path, self.verbose)
86  self.df_path = join(self.model_path, df_path)
87  self.robot = builder(
88  self.df_path,
89  [join(self.model_path, "../..")],
90  pin.JointModelFreeFlyer() if self.free_flyer else None,
91  )
92  else:
93  df_path = join(self.path, self.sdf_subpath, self.sdf_filename)
94  try:
95  builder = RobotWrapper.BuildFromSDF
96  if self.model_path is None:
97  self.model_path = getModelPath(df_path, self.verbose)
98  self.df_path = join(self.model_path, df_path)
99  if tuple(int(i) for i in pin.__version__.split(".")) > (2, 9, 1):
100  self.robot = builder(
101  self.df_path,
102  package_dirs=[join(self.model_path, "../..")],
103  root_joint=pin.JointModelFreeFlyer()
104  if self.free_flyer
105  else None,
106  root_link_name=self.sdf_root_link_name,
107  parent_guidance=self.sdf_parent_guidance,
108  )
109  else:
110  self.robot = builder(
111  self.df_path,
112  package_dirs=[join(self.model_path, "../..")],
113  root_joint=pin.JointModelFreeFlyer()
114  if self.free_flyer
115  else None,
116  )
117  except AttributeError:
118  raise ImportError("Building SDF models require pinocchio >= 3.0.0")
119 
120  if self.srdf_filename:
121  self.srdf_path = join(
122  self.model_path, self.path, self.srdf_subpath, self.srdf_filename
123  )
124  self.robot.q0 = readParamsFromSrdf(
125  self.robot.model,
126  self.srdf_path,
127  self.verbose,
129  self.ref_posture,
130  )
131 
132  if pin.WITH_HPP_FCL and pin.WITH_HPP_FCL_BINDINGS:
133  # Add all collision pairs
134  self.robot.collision_model.addAllCollisionPairs()
135 
136  # Remove collision pairs per SRDF
137  pin.removeCollisionPairs(
138  self.robot.model, self.robot.collision_model, self.srdf_path, False
139  )
140 
141  # Recreate collision data since the collision pairs changed
142  self.robot.collision_data = self.robot.collision_model.createData()
143  else:
144  self.srdf_path = None
145  self.robot.q0 = pin.neutral(self.robot.model)
146 
147  if self.free_flyer:
149 
151  ub = self.robot.model.upperPositionLimit
152  ub[:7] = 1
153  self.robot.model.upperPositionLimit = ub
154  lb = self.robot.model.lowerPositionLimit
155  lb[:7] = -1
156  self.robot.model.lowerPositionLimit = lb
157 
158 
160  path = "a1_description"
161  urdf_filename = "a1.urdf"
162  urdf_subpath = "urdf"
163  srdf_filename = "a1.srdf"
164  ref_posture = "standing"
165  free_flyer = True
166 
167 
169  path = "anymal_b_simple_description"
170  urdf_filename = "anymal.urdf"
171  srdf_filename = "anymal.srdf"
172  ref_posture = "standing"
173  free_flyer = True
174 
175 
177  path = "laikago_description"
178  urdf_subpath = "urdf"
179  urdf_filename = "laikago.urdf"
180  free_flyer = True
181 
182 
184  urdf_filename = "anymal-kinova.urdf"
185  srdf_filename = "anymal-kinova.srdf"
186  ref_posture = "standing_with_arm_up"
187 
188 
190  path = "baxter_description"
191  urdf_filename = "baxter.urdf"
192  urdf_subpath = "urdf"
193 
194 
196  path = "cassie_description"
197  if tuple(int(i) for i in pin.__version__.split(".")) > (2, 9, 1):
198  sdf_filename = "cassie.sdf"
199  else:
200  sdf_filename = "cassie_v2.sdf"
201  sdf_subpath = "robots"
202  srdf_filename = "cassie_v2.srdf"
203  ref_posture = "standing"
204  free_flyer = True
205  sdf_root_link_name = "pelvis"
206  sdf_parent_guidance = [
207  "left-roll-op",
208  "left-yaw-op",
209  "left-pitch-op",
210  "left-knee-op",
211  "left-tarsus-spring-joint",
212  "left-foot-op",
213  "right-roll-op",
214  "right-yaw-op",
215  "right-pitch-op",
216  "right-knee-op",
217  "right-tarsus-spring-joint",
218  "right-foot-op",
219  ]
220 
221 
223  path = "talos_data"
224  urdf_filename = "talos_reduced.urdf"
225  srdf_filename = "talos.srdf"
226  free_flyer = True
227  has_rotor_parameters = True
228 
229 
231  path = "asr_twodof_description"
232  urdf_filename = "TwoDofs.urdf"
233  urdf_subpath = "urdf"
234 
235 
237  urdf_filename = "talos_reduced_box.urdf"
238 
239 
241  urdf_filename = "talos_full_v2.urdf"
242 
243 
245  urdf_filename = "talos_full_v2_box.urdf"
246 
247 
249  urdf_filename = "talos_left_arm.urdf"
250  free_flyer = False
251 
252 
254  def __init__(self):
255  super(TalosLegsLoader, self).__init__()
256  legMaxId = 14
257  m1 = self.robot.model
258  m2 = pin.Model()
259  for j, M, name, parent, Y in zip(
260  m1.joints, m1.jointPlacements, m1.names, m1.parents, m1.inertias
261  ):
262  if j.id < legMaxId:
263  jid = m2.addJoint(parent, getattr(pin, j.shortname())(), M, name)
264  idx_q, idx_v = m2.joints[jid].idx_q, m2.joints[jid].idx_v
265  m2.upperPositionLimit[idx_q : idx_q + j.nq] = m1.upperPositionLimit[
266  j.idx_q : j.idx_q + j.nq
267  ]
268  m2.lowerPositionLimit[idx_q : idx_q + j.nq] = m1.lowerPositionLimit[
269  j.idx_q : j.idx_q + j.nq
270  ]
271  m2.velocityLimit[idx_v : idx_v + j.nv] = m1.velocityLimit[
272  j.idx_v : j.idx_v + j.nv
273  ]
274  m2.effortLimit[idx_v : idx_v + j.nv] = m1.effortLimit[
275  j.idx_v : j.idx_v + j.nv
276  ]
277  assert jid == j.id
278  m2.appendBodyToJoint(jid, Y, pin.SE3.Identity())
279 
280  upperPos = m2.upperPositionLimit
281  upperPos[:7] = 1
282  m2.upperPositionLimit = upperPos
283  lowerPos = m2.lowerPositionLimit
284  lowerPos[:7] = -1
285  m2.lowerPositionLimit = lowerPos
286  effort = m2.effortLimit
287  effort[:6] = np.inf
288  m2.effortLimit = effort
289 
290  # q2 = self.robot.q0[:19]
291  for f in m1.frames:
292  if f.parent < legMaxId:
293  m2.addFrame(f)
294 
295  g2 = pin.GeometryModel()
296  for g in self.robot.visual_model.geometryObjects:
297  if g.parentJoint < 14:
298  g2.addGeometryObject(g)
299 
300  self.robot.model = m2
301  self.robot.data = m2.createData()
302  self.robot.visual_model = g2
303  # self.robot.q0=q2
304  self.robot.visual_data = pin.GeometryData(g2)
305 
306  # Load SRDF file
307  self.robot.q0 = readParamsFromSrdf(
308  self.robot.model,
309  self.srdf_path,
310  self.verbose,
312  self.ref_posture,
313  )
314 
315  assert (m2.armature[:6] == 0.0).all()
316  # Add the free-flyer joint limits to the new model
318 
319 
321  path = "hyq_description"
322  urdf_filename = "hyq_no_sensors.urdf"
323  srdf_filename = "hyq.srdf"
324  ref_posture = "standing"
325  free_flyer = True
326 
327 
329  path = "bolt_description"
330  urdf_filename = "bolt.urdf"
331  srdf_filename = "bolt.srdf"
332  ref_posture = "standing"
333  free_flyer = True
334 
335 
337  path = "solo_description"
338  urdf_filename = "solo.urdf"
339  srdf_filename = "solo.srdf"
340  ref_posture = "standing"
341  free_flyer = True
342 
343 
345  urdf_filename = "solo12.urdf"
346 
347 
349  path = "finger_edu_description"
350  urdf_filename = "finger_edu.urdf"
351  srdf_filename = "finger_edu.srdf"
352  ref_posture = "hanging"
353  free_flyer = False
354 
355 
357  path = "kinova_description"
358  urdf_filename = "kinova.urdf"
359  srdf_filename = "kinova.srdf"
360  ref_posture = "arm_up"
361 
362 
364  path = "tiago_description"
365  urdf_filename = "tiago.urdf"
366 
367 
369  urdf_filename = "tiago_dual.urdf"
370 
371 
373  urdf_filename = "tiago_no_hand.urdf"
374 
375 
377  path = "icub_description"
378  urdf_filename = "icub.urdf"
379  srdf_filename = "icub.srdf"
380  free_flyer = True
381 
382 
384  urdf_filename = "icub_reduced.urdf"
385 
386 
388  path = "panda_description"
389  urdf_filename = "panda.urdf"
390  urdf_subpath = "urdf"
391 
392 
394  path = "ur_description"
395  urdf_filename = "ur3_robot.urdf"
396  urdf_subpath = "urdf"
397  ref_posture = None
398 
399 
401  urdf_filename = "ur3_gripper.urdf"
402  srdf_filename = "ur3_gripper.srdf"
403 
404 
406  urdf_filename = "ur3_joint_limited_robot.urdf"
407 
408 
410  urdf_filename = "ur5_robot.urdf"
411  srdf_filename = "ur5.srdf"
412 
413 
415  urdf_filename = "ur5_gripper.urdf"
416  srdf_filename = "ur5_gripper.srdf"
417 
418 
420  urdf_filename = "ur5_joint_limited_robot.urdf"
421 
422 
424  urdf_filename = "ur10_robot.urdf"
425 
426 
428  urdf_filename = "ur10_joint_limited_robot.urdf"
429 
430 
432  path = "hector_description"
433  urdf_filename = "quadrotor_base.urdf"
434  free_flyer = True
435 
436 
438  path = "double_pendulum_description"
439  urdf_filename = "double_pendulum.urdf"
440  urdf_subpath = "urdf"
441 
442 
444  urdf_filename = "double_pendulum_continuous.urdf"
445 
446 
448  urdf_filename = "double_pendulum_simple.urdf"
449 
450 
452  path = "romeo_description"
453  urdf_filename = "romeo.urdf"
454  urdf_subpath = "urdf"
455  free_flyer = True
456 
457 
459  path = "simple_humanoid_description"
460  urdf_subpath = "urdf"
461  urdf_filename = "simple_humanoid.urdf"
462  srdf_filename = "simple_humanoid.srdf"
463  free_flyer = True
464 
465 
467  urdf_filename = "simple_humanoid_classical.urdf"
468  srdf_filename = "simple_humanoid_classical.srdf"
469 
470 
472  path = "iris_description"
473  urdf_filename = "iris_simple.urdf"
474  free_flyer = True
475 
476 
477 ROBOTS = {
478  "a1": A1Loader,
479  "anymal": ANYmalLoader,
480  "anymal_kinova": ANYmalKinovaLoader,
481  "asr_twodof": AsrTwoDofLoader,
482  "baxter": BaxterLoader,
483  "cassie": CassieLoader,
484  "double_pendulum": DoublePendulumLoader,
485  "double_pendulum_continuous": DoublePendulumContinuousLoader,
486  "double_pendulum_simple": DoublePendulumSimpleLoader,
487  "hector": HectorLoader,
488  "hyq": HyQLoader,
489  "icub": ICubLoader,
490  "icub_reduced": ICubReducedLoader,
491  "iris": IrisLoader,
492  "kinova": KinovaLoader,
493  "laikago": LaikagoLoader,
494  "panda": PandaLoader,
495  "romeo": RomeoLoader,
496  "simple_humanoid": SimpleHumanoidLoader,
497  "simple_humanoid_classical": SimpleHumanoidClassicalLoader,
498  "bolt": BoltLoader,
499  "solo8": Solo8Loader,
500  "solo12": Solo12Loader,
501  "finger_edu": FingerEduLoader,
502  "talos": TalosLoader,
503  "talos_box": TalosBoxLoader,
504  "talos_arm": TalosArmLoader,
505  "talos_legs": TalosLegsLoader,
506  "talos_full": TalosFullLoader,
507  "talos_full_box": TalosFullBoxLoader,
508  "tiago": TiagoLoader,
509  "tiago_dual": TiagoDualLoader,
510  "tiago_no_hand": TiagoNoHandLoader,
511  "ur3": UR5Loader,
512  "ur3_gripper": UR3GripperLoader,
513  "ur3_limited": UR3LimitedLoader,
514  "ur5": UR5Loader,
515  "ur5_gripper": UR5GripperLoader,
516  "ur5_limited": UR5LimitedLoader,
517  "ur10": UR10Loader,
518  "ur10_limited": UR10LimitedLoader,
519 }
520 
521 
522 def loader(name, display=False, rootNodeName=""):
523  """Load a robot by its name, and optionnaly display it in a viewer."""
524  if name not in ROBOTS:
525  robots = ", ".join(sorted(ROBOTS.keys()))
526  raise ValueError(
527  "Robot '%s' not found. Possible values are %s" % (name, robots)
528  )
529  inst = ROBOTS[name]()
530  if display:
531  if rootNodeName:
532  inst.robot.initViewer()
533  inst.robot.viz.loadViewerModel(rootNodeName=rootNodeName)
534  else:
535  inst.robot.initViewer(loadModel=True)
536  inst.robot.display(inst.robot.q0)
537  return inst
538 
539 
540 def load(name, display=False, rootNodeName=""):
541  """Load a robot by its name, and optionnaly display it in a viewer."""
542  return loader(name, display, rootNodeName).robot
543 
544 
545 def load_full(name, display=False, rootNodeName=""):
546  """Load a robot by its name, optionnaly display it in a viewer,
547  and provide its q0 and paths."""
548  inst = loader(name, display, rootNodeName)
549  return inst.robot, inst.robot.q0, inst.df_path, inst.srdf_path
def readParamsFromSrdf(model, SRDF_PATH, verbose=False, has_rotor_parameters=True, referencePose="half_sitting")
def getModelPath(subpath, printmsg=False)
def load(name, display=False, rootNodeName="")
def loader(name, display=False, rootNodeName="")
def load_full(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 Fri Jun 23 2023 02:38:32