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 try:
9  from .path import EXAMPLE_ROBOT_DATA_MODEL_DIR, EXAMPLE_ROBOT_DATA_SOURCE_DIR
10 except ImportError:
11  pass
12 
13 
14 def getModelPath(subpath, verbose=False):
15  source = dirname(dirname(dirname(__file__))) # top level source directory
16  paths = [
17  # function called from "make release" in build/ dir
18  join(dirname(dirname(dirname(source))), "robots"),
19  # function called from a build/ dir inside top level source
20  join(dirname(source), "robots"),
21  # function called from top level source dir
22  join(source, "robots"),
23  ]
24  try:
25  EXAMPLE_ROBOT_DATA_MODEL_DIR
26 
27  # function called from installed project
28  paths.append(EXAMPLE_ROBOT_DATA_MODEL_DIR)
29  # function called from off-tree build dir
30  paths.append(EXAMPLE_ROBOT_DATA_SOURCE_DIR)
31  except NameError:
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 verbose:
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  model_path = None
76 
77  def __init__(self, verbose=False):
78  self.verbose = verbose
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=(
104  pin.JointModelFreeFlyer() if self.free_flyer else None
105  ),
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=(
114  pin.JointModelFreeFlyer() if self.free_flyer else None
115  ),
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  root = getModelPath(self.path)
147  self.robot.urdf = join(root, self.path, self.urdf_subpath, self.urdf_filename)
148 
149  if self.free_flyer:
151 
153  ub = self.robot.model.upperPositionLimit
154  ub[:7] = 1
155  self.robot.model.upperPositionLimit = ub
156  lb = self.robot.model.lowerPositionLimit
157  lb[:7] = -1
158  self.robot.model.lowerPositionLimit = lb
159 
160 
162  path = "b1_description"
163  urdf_filename = "b1.urdf"
164  urdf_subpath = "urdf"
165  srdf_filename = "b1.srdf"
166  ref_posture = "standing"
167  free_flyer = True
168 
169 
171  path = "go1_description"
172  urdf_filename = "go1.urdf"
173  urdf_subpath = "urdf"
174  srdf_filename = "go1.srdf"
175  ref_posture = "standing"
176  free_flyer = True
177 
178 
180  path = "a1_description"
181  urdf_filename = "a1.urdf"
182  urdf_subpath = "urdf"
183  srdf_filename = "a1.srdf"
184  ref_posture = "standing"
185  free_flyer = True
186 
187 
189  path = "z1_description"
190  urdf_filename = "z1.urdf"
191  urdf_subpath = "urdf"
192  srdf_filename = "z1.srdf"
193  ref_posture = "arm_up"
194 
195 
197  urdf_filename = "b1-z1.urdf"
198  srdf_filename = "b1-z1.srdf"
199  ref_posture = "standing_with_arm_home"
200 
201 
203  path = "anymal_b_simple_description"
204  urdf_filename = "anymal.urdf"
205  srdf_filename = "anymal.srdf"
206  ref_posture = "standing"
207  free_flyer = True
208 
209 
211  path = "anymal_c_simple_description"
212  urdf_subpath = "urdf"
213  urdf_filename = "anymal.urdf"
214  srdf_filename = "anymal.srdf"
215  ref_posture = "standing"
216  free_flyer = True
217 
218 
220  path = "laikago_description"
221  urdf_subpath = "urdf"
222  urdf_filename = "laikago.urdf"
223  free_flyer = True
224 
225 
227  urdf_filename = "anymal-kinova.urdf"
228  srdf_filename = "anymal-kinova.srdf"
229  ref_posture = "standing_with_arm_up"
230 
231 
233  path = "baxter_description"
234  urdf_filename = "baxter.urdf"
235  urdf_subpath = "urdf"
236 
237 
239  path = "cassie_description"
240  if tuple(int(i) for i in pin.__version__.split(".")) > (2, 9, 1):
241  sdf_filename = "cassie.sdf"
242  else:
243  sdf_filename = "cassie_v2.sdf"
244  sdf_subpath = "robots"
245  srdf_filename = "cassie_v2.srdf"
246  ref_posture = "standing"
247  free_flyer = True
248  sdf_root_link_name = "pelvis"
249  sdf_parent_guidance = [
250  "left-roll-op",
251  "left-yaw-op",
252  "left-pitch-op",
253  "left-knee-op",
254  "left-tarsus-spring-joint",
255  "left-foot-op",
256  "right-roll-op",
257  "right-yaw-op",
258  "right-pitch-op",
259  "right-knee-op",
260  "right-tarsus-spring-joint",
261  "right-foot-op",
262  ]
263 
264 
266  path = "talos_data"
267  urdf_filename = "talos_reduced.urdf"
268  srdf_filename = "talos.srdf"
269  free_flyer = True
270  has_rotor_parameters = True
271 
272 
274  path = "asr_twodof_description"
275  urdf_filename = "TwoDofs.urdf"
276  urdf_subpath = "urdf"
277 
278 
280  urdf_filename = "talos_reduced_box.urdf"
281 
282 
284  urdf_filename = "talos_full_v2.urdf"
285 
286 
288  urdf_filename = "talos_full_v2_box.urdf"
289 
290 
292  urdf_filename = "talos_left_arm.urdf"
293  free_flyer = False
294 
295 
297  def __init__(self, verbose=False):
298  super(TalosLegsLoader, self).__init__(verbose=verbose)
299  legMaxId = 14
300  m1 = self.robot.model
301  m2 = pin.Model()
302  for j, M, name, parent, Y in zip(
303  m1.joints, m1.jointPlacements, m1.names, m1.parents, m1.inertias
304  ):
305  if j.id < legMaxId:
306  jid = m2.addJoint(parent, getattr(pin, j.shortname())(), M, name)
307  idx_q, idx_v = m2.joints[jid].idx_q, m2.joints[jid].idx_v
308  m2.upperPositionLimit[idx_q : idx_q + j.nq] = m1.upperPositionLimit[
309  j.idx_q : j.idx_q + j.nq
310  ]
311  m2.lowerPositionLimit[idx_q : idx_q + j.nq] = m1.lowerPositionLimit[
312  j.idx_q : j.idx_q + j.nq
313  ]
314  m2.velocityLimit[idx_v : idx_v + j.nv] = m1.velocityLimit[
315  j.idx_v : j.idx_v + j.nv
316  ]
317  m2.effortLimit[idx_v : idx_v + j.nv] = m1.effortLimit[
318  j.idx_v : j.idx_v + j.nv
319  ]
320  assert jid == j.id
321  m2.appendBodyToJoint(jid, Y, pin.SE3.Identity())
322 
323  upperPos = m2.upperPositionLimit
324  upperPos[:7] = 1
325  m2.upperPositionLimit = upperPos
326  lowerPos = m2.lowerPositionLimit
327  lowerPos[:7] = -1
328  m2.lowerPositionLimit = lowerPos
329  effort = m2.effortLimit
330  effort[:6] = np.inf
331  m2.effortLimit = effort
332 
333  # q2 = self.robot.q0[:19]
334  for f in m1.frames:
335  if f.parent < legMaxId:
336  m2.addFrame(f)
337 
338  g2 = pin.GeometryModel()
339  for g in self.robot.visual_model.geometryObjects:
340  if g.parentJoint < 14:
341  g2.addGeometryObject(g)
342 
343  self.robot.model = m2
344  self.robot.data = m2.createData()
345  self.robot.visual_model = g2
346  # self.robot.q0=q2
347  self.robot.visual_data = pin.GeometryData(g2)
348 
349  # Load SRDF file
350  self.robot.q0 = readParamsFromSrdf(
351  self.robot.model,
352  self.srdf_path,
353  self.verbose,
355  self.ref_posture,
356  )
357 
358  assert (m2.armature[:6] == 0.0).all()
359  # Add the free-flyer joint limits to the new model
361 
362 
364  path = "hyq_description"
365  urdf_filename = "hyq_no_sensors.urdf"
366  srdf_filename = "hyq.srdf"
367  ref_posture = "standing"
368  free_flyer = True
369 
370 
372  path = "bolt_description"
373  urdf_filename = "bolt.urdf"
374  srdf_filename = "bolt.srdf"
375  ref_posture = "standing"
376  free_flyer = True
377 
378 
380  path = "borinot_description"
381  urdf_subpath = "urdf"
382  srdf_subpath = "srdf"
383  urdf_filename = "borinot_flying_arm_2.urdf"
384  srdf_filename = "borinot_flying_arm_2.srdf"
385  ref_posture = "home"
386  free_flyer = True
387 
388 
390  path = "solo_description"
391  urdf_filename = "solo.urdf"
392  srdf_filename = "solo.srdf"
393  ref_posture = "standing"
394  free_flyer = True
395 
396 
398  urdf_filename = "solo12.urdf"
399 
400 
402  path = "finger_edu_description"
403  urdf_filename = "finger_edu.urdf"
404  srdf_filename = "finger_edu.srdf"
405  ref_posture = "hanging"
406  free_flyer = False
407 
408 
410  path = "kinova_description"
411  urdf_filename = "kinova.urdf"
412  srdf_filename = "kinova.srdf"
413  ref_posture = "arm_up"
414 
415 
417  path = "tiago_description"
418  urdf_filename = "tiago.urdf"
419 
420 
422  urdf_filename = "tiago_dual.urdf"
423 
424 
426  urdf_filename = "tiago_no_hand.urdf"
427 
428 
430  path = "icub_description"
431  urdf_filename = "icub.urdf"
432  srdf_filename = "icub.srdf"
433  free_flyer = True
434 
435 
437  urdf_filename = "icub_reduced.urdf"
438 
439 
441  path = "panda_description"
442  urdf_filename = "panda.urdf"
443  urdf_subpath = "urdf"
444  srdf_filename = "panda.srdf"
445  ref_posture = "default"
446 
447 
449  path = "allegro_hand_description"
450  urdf_filename = "allegro_right_hand.urdf"
451  urdf_subpath = "urdf"
452 
453 
455  path = "allegro_hand_description"
456  urdf_filename = "allegro_left_hand.urdf"
457  urdf_subpath = "urdf"
458 
459 
461  path = "ur_description"
462  urdf_filename = "ur3_robot.urdf"
463  urdf_subpath = "urdf"
464  ref_posture = None
465 
466 
468  urdf_filename = "ur3_gripper.urdf"
469  srdf_filename = "ur3_gripper.srdf"
470 
471 
473  urdf_filename = "ur3_joint_limited_robot.urdf"
474 
475 
477  urdf_filename = "ur5_robot.urdf"
478  srdf_filename = "ur5.srdf"
479 
480 
482  urdf_filename = "ur5_gripper.urdf"
483  srdf_filename = "ur5_gripper.srdf"
484 
485 
487  urdf_filename = "ur5_joint_limited_robot.urdf"
488 
489 
491  urdf_filename = "ur10_robot.urdf"
492 
493 
495  urdf_filename = "ur10_joint_limited_robot.urdf"
496 
497 
499  path = "hector_description"
500  urdf_filename = "quadrotor_base.urdf"
501  free_flyer = True
502 
503 
505  path = "hextilt_description"
506  urdf_subpath = "urdf"
507  srdf_subpath = "srdf"
508  urdf_filename = "hextilt_flying_arm_5.urdf"
509  srdf_filename = "hextilt_flying_arm_5.srdf"
510  ref_posture = "home"
511  free_flyer = True
512 
513 
515  path = "double_pendulum_description"
516  urdf_filename = "double_pendulum.urdf"
517  urdf_subpath = "urdf"
518 
519 
521  urdf_filename = "double_pendulum_continuous.urdf"
522 
523 
525  urdf_filename = "double_pendulum_simple.urdf"
526 
527 
529  path = "quadruped_description"
530  urdf_subpath = "urdf"
531  urdf_filename = "quadruped.urdf"
532  free_flyer = True
533 
534 
536  path = "romeo_description"
537  urdf_filename = "romeo.urdf"
538  urdf_subpath = "urdf"
539  free_flyer = True
540 
541 
543  path = "simple_humanoid_description"
544  urdf_subpath = "urdf"
545  urdf_filename = "simple_humanoid.urdf"
546  srdf_filename = "simple_humanoid.srdf"
547  free_flyer = True
548 
549 
551  urdf_filename = "simple_humanoid_classical.urdf"
552  srdf_filename = "simple_humanoid_classical.srdf"
553 
554 
556  path = "iris_description"
557  urdf_filename = "iris_simple.urdf"
558  free_flyer = True
559 
560 
561 ROBOTS = {
562  "b1": B1Loader,
563  "go1": Go1Loader,
564  "a1": A1Loader,
565  "z1": Z1Loader,
566  "b1_z1": B1Z1Loader,
567  "anymal": ANYmalLoader,
568  "anymal_c": ANYmalCLoader,
569  "anymal_kinova": ANYmalKinovaLoader,
570  "asr_twodof": AsrTwoDofLoader,
571  "baxter": BaxterLoader,
572  "cassie": CassieLoader,
573  "double_pendulum": DoublePendulumLoader,
574  "double_pendulum_continuous": DoublePendulumContinuousLoader,
575  "double_pendulum_simple": DoublePendulumSimpleLoader,
576  "hector": HectorLoader,
577  "hextilt": HextiltLoader,
578  "hyq": HyQLoader,
579  "icub": ICubLoader,
580  "icub_reduced": ICubReducedLoader,
581  "iris": IrisLoader,
582  "kinova": KinovaLoader,
583  "laikago": LaikagoLoader,
584  "panda": PandaLoader,
585  "allegro_right_hand": AllegroRightHandLoader,
586  "allegro_left_hand": AllegroLeftHandLoader,
587  "quadruped": QuadrupedLoader,
588  "romeo": RomeoLoader,
589  "simple_humanoid": SimpleHumanoidLoader,
590  "simple_humanoid_classical": SimpleHumanoidClassicalLoader,
591  "bolt": BoltLoader,
592  "borinot": BorinotLoader,
593  "solo8": Solo8Loader,
594  "solo12": Solo12Loader,
595  "finger_edu": FingerEduLoader,
596  "talos": TalosLoader,
597  "talos_box": TalosBoxLoader,
598  "talos_arm": TalosArmLoader,
599  "talos_legs": TalosLegsLoader,
600  "talos_full": TalosFullLoader,
601  "talos_full_box": TalosFullBoxLoader,
602  "tiago": TiagoLoader,
603  "tiago_dual": TiagoDualLoader,
604  "tiago_no_hand": TiagoNoHandLoader,
605  "ur3": UR5Loader,
606  "ur3_gripper": UR3GripperLoader,
607  "ur3_limited": UR3LimitedLoader,
608  "ur5": UR5Loader,
609  "ur5_gripper": UR5GripperLoader,
610  "ur5_limited": UR5LimitedLoader,
611  "ur10": UR10Loader,
612  "ur10_limited": UR10LimitedLoader,
613 }
614 
615 
616 def loader(name, display=False, rootNodeName="", verbose=False):
617  """Load a robot by its name, and optionally display it in a viewer."""
618  if name not in ROBOTS:
619  robots = ", ".join(sorted(ROBOTS.keys()))
620  raise ValueError(
621  "Robot '%s' not found. Possible values are %s" % (name, robots)
622  )
623  inst = ROBOTS[name](verbose=verbose)
624  if display:
625  if rootNodeName:
626  inst.robot.initViewer()
627  inst.robot.viz.loadViewerModel(rootNodeName=rootNodeName)
628  else:
629  inst.robot.initViewer(loadModel=True)
630  inst.robot.display(inst.robot.q0)
631  return inst
632 
633 
634 def load(name, display=False, rootNodeName="", verbose=False):
635  """Load a robot by its name, and optionnaly display it in a viewer."""
636  return loader(name, display, rootNodeName, verbose).robot
637 
638 
639 def load_full(name, display=False, rootNodeName="", verbose=False):
640  """Load a robot by its name, optionnaly display it in a viewer,
641  and provide its q0 and paths."""
642  inst = loader(name, display, rootNodeName, verbose)
643  return inst.robot, inst.robot.q0, inst.df_path, inst.srdf_path
example_robot_data.robots_loader.RobotLoader.urdf_subpath
string urdf_subpath
Definition: robots_loader.py:69
example_robot_data.robots_loader.Z1Loader
Definition: robots_loader.py:188
example_robot_data.robots_loader.SimpleHumanoidLoader
Definition: robots_loader.py:542
example_robot_data.robots_loader.KinovaLoader
Definition: robots_loader.py:409
example_robot_data.robots_loader.UR3GripperLoader
Definition: robots_loader.py:467
example_robot_data.robots_loader.UR10LimitedLoader
Definition: robots_loader.py:494
example_robot_data.robots_loader.load_full
def load_full(name, display=False, rootNodeName="", verbose=False)
Definition: robots_loader.py:639
example_robot_data.robots_loader.DoublePendulumSimpleLoader
Definition: robots_loader.py:524
example_robot_data.robots_loader.UR5GripperLoader
Definition: robots_loader.py:481
example_robot_data.robots_loader.RobotLoader.sdf_root_link_name
string sdf_root_link_name
Definition: robots_loader.py:67
example_robot_data.robots_loader.RobotLoader.sdf_filename
string sdf_filename
Definition: robots_loader.py:66
example_robot_data.robots_loader.loader
def loader(name, display=False, rootNodeName="", verbose=False)
Definition: robots_loader.py:616
example_robot_data.robots_loader.ANYmalKinovaLoader
Definition: robots_loader.py:226
example_robot_data.robots_loader.HectorLoader
Definition: robots_loader.py:498
example_robot_data.robots_loader.RobotLoader.srdf_path
srdf_path
Definition: robots_loader.py:121
example_robot_data.robots_loader.AsrTwoDofLoader
Definition: robots_loader.py:273
example_robot_data.robots_loader.TalosArmLoader
Definition: robots_loader.py:291
example_robot_data.robots_loader.ANYmalLoader
Definition: robots_loader.py:202
example_robot_data.robots_loader.LaikagoLoader
Definition: robots_loader.py:219
example_robot_data.robots_loader.Solo12Loader
Definition: robots_loader.py:397
example_robot_data.robots_loader.RobotLoader.verbose
verbose
Definition: robots_loader.py:78
example_robot_data.robots_loader.TiagoNoHandLoader
Definition: robots_loader.py:425
example_robot_data.robots_loader.ICubLoader
Definition: robots_loader.py:429
example_robot_data.robots_loader.TiagoDualLoader
Definition: robots_loader.py:421
example_robot_data.robots_loader.CassieLoader
Definition: robots_loader.py:238
example_robot_data.robots_loader.B1Loader
Definition: robots_loader.py:161
example_robot_data.robots_loader.TalosLoader
Definition: robots_loader.py:265
example_robot_data.robots_loader.load
def load(name, display=False, rootNodeName="", verbose=False)
Definition: robots_loader.py:634
example_robot_data.robots_loader.HextiltLoader
Definition: robots_loader.py:504
example_robot_data.robots_loader.RobotLoader.robot
robot
Definition: robots_loader.py:87
example_robot_data.robots_loader.HyQLoader
Definition: robots_loader.py:363
example_robot_data.robots_loader.ICubReducedLoader
Definition: robots_loader.py:436
example_robot_data.robots_loader.UR5LimitedLoader
Definition: robots_loader.py:486
example_robot_data.robots_loader.QuadrupedLoader
Definition: robots_loader.py:528
example_robot_data.robots_loader.B1Z1Loader
Definition: robots_loader.py:196
example_robot_data.robots_loader.Solo8Loader
Definition: robots_loader.py:389
example_robot_data.robots_loader.ANYmalCLoader
Definition: robots_loader.py:210
example_robot_data.robots_loader.PandaLoader
Definition: robots_loader.py:440
example_robot_data.robots_loader.RobotLoader.has_rotor_parameters
bool has_rotor_parameters
Definition: robots_loader.py:73
example_robot_data.robots_loader.AllegroRightHandLoader
Definition: robots_loader.py:448
pinocchio.robot_wrapper
Definition: bindings/python/pinocchio/robot_wrapper.py:1
example_robot_data.robots_loader.RobotLoader.model_path
model_path
Definition: robots_loader.py:75
example_robot_data.robots_loader.SimpleHumanoidClassicalLoader
Definition: robots_loader.py:550
example_robot_data.robots_loader.FingerEduLoader
Definition: robots_loader.py:401
example_robot_data.robots_loader.Go1Loader
Definition: robots_loader.py:170
example_robot_data.robots_loader.RobotLoader.free_flyer
bool free_flyer
Definition: robots_loader.py:74
example_robot_data.robots_loader.RobotLoader.srdf_subpath
string srdf_subpath
Definition: robots_loader.py:70
example_robot_data.robots_loader.TalosBoxLoader
Definition: robots_loader.py:279
example_robot_data.robots_loader.TalosFullBoxLoader
Definition: robots_loader.py:287
example_robot_data.robots_loader.IrisLoader
Definition: robots_loader.py:555
example_robot_data.robots_loader.RobotLoader.path
string path
Definition: robots_loader.py:63
example_robot_data.robots_loader.RobotLoader.sdf_parent_guidance
list sdf_parent_guidance
Definition: robots_loader.py:68
example_robot_data.robots_loader.UR10Loader
Definition: robots_loader.py:490
example_robot_data.robots_loader.RobotLoader.urdf_filename
string urdf_filename
Definition: robots_loader.py:64
example_robot_data.robots_loader.UR5Loader
Definition: robots_loader.py:476
example_robot_data.robots_loader.getModelPath
def getModelPath(subpath, verbose=False)
Definition: robots_loader.py:14
example_robot_data.robots_loader.UR3Loader
Definition: robots_loader.py:460
pinocchio::copy
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:42
example_robot_data.robots_loader.DoublePendulumContinuousLoader
Definition: robots_loader.py:520
example_robot_data.robots_loader.BoltLoader
Definition: robots_loader.py:371
example_robot_data.robots_loader.RobotLoader.srdf_filename
string srdf_filename
Definition: robots_loader.py:65
example_robot_data.robots_loader.RobotLoader.ref_posture
string ref_posture
Definition: robots_loader.py:72
example_robot_data.robots_loader.RomeoLoader
Definition: robots_loader.py:535
example_robot_data.robots_loader.BorinotLoader
Definition: robots_loader.py:379
example_robot_data.robots_loader.TalosLegsLoader.__init__
def __init__(self, verbose=False)
Definition: robots_loader.py:297
example_robot_data.robots_loader.readParamsFromSrdf
def readParamsFromSrdf(model, SRDF_PATH, verbose=False, has_rotor_parameters=True, referencePose="half_sitting")
Definition: robots_loader.py:42
example_robot_data.robots_loader.UR3LimitedLoader
Definition: robots_loader.py:472
example_robot_data.robots_loader.TalosFullLoader
Definition: robots_loader.py:283
example_robot_data.robots_loader.AllegroLeftHandLoader
Definition: robots_loader.py:454
example_robot_data.robots_loader.RobotLoader.sdf_subpath
string sdf_subpath
Definition: robots_loader.py:71
example_robot_data.robots_loader.RobotLoader
Definition: robots_loader.py:62
example_robot_data.robots_loader.TalosLegsLoader
Definition: robots_loader.py:296
example_robot_data.robots_loader.RobotLoader.__init__
def __init__(self, verbose=False)
Definition: robots_loader.py:77
example_robot_data.robots_loader.TiagoLoader
Definition: robots_loader.py:416
example_robot_data.robots_loader.DoublePendulumLoader
Definition: robots_loader.py:514
example_robot_data.robots_loader.BaxterLoader
Definition: robots_loader.py:232
example_robot_data.robots_loader.RobotLoader.df_path
df_path
Definition: robots_loader.py:86
example_robot_data.robots_loader.A1Loader
Definition: robots_loader.py:179
example_robot_data.robots_loader.RobotLoader.addFreeFlyerJointLimits
def addFreeFlyerJointLimits(self)
Definition: robots_loader.py:152


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