2 from os.path
import dirname, exists, join
5 import pinocchio
as pin
9 from .path
import EXAMPLE_ROBOT_DATA_MODEL_DIR, EXAMPLE_ROBOT_DATA_SOURCE_DIR
15 source = dirname(dirname(dirname(__file__)))
18 join(dirname(dirname(dirname(source))),
"robots"),
20 join(dirname(source),
"robots"),
22 join(source,
"robots"),
25 EXAMPLE_ROBOT_DATA_MODEL_DIR
28 paths.append(EXAMPLE_ROBOT_DATA_MODEL_DIR)
30 paths.append(EXAMPLE_ROBOT_DATA_SOURCE_DIR)
33 paths += [join(p,
"../../../share/example-robot-data/robots")
for p
in sys.path]
35 if exists(join(path, subpath.strip(
"/"))):
37 print(
"using %s as modelPath" % path)
39 raise IOError(
"%s not found" % subpath)
46 has_rotor_parameters=True,
47 referencePose="half_sitting",
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)
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)
67 sdf_root_link_name =
""
68 sdf_parent_guidance = []
69 urdf_subpath =
"robots"
72 ref_posture =
"half_sitting"
73 has_rotor_parameters =
False
81 raise AttributeError(
"Please choose between URDF *or* SDF")
83 builder = RobotWrapper.BuildFromURDF
90 pin.JointModelFreeFlyer()
if self.
free_flyer else None,
95 builder = RobotWrapper.BuildFromSDF
99 if tuple(int(i)
for i
in pin.__version__.split(
".")) > (2, 9, 1):
100 self.
robot = builder(
102 package_dirs=[join(self.
model_path,
"../..")],
104 pin.JointModelFreeFlyer()
if self.
free_flyer else None
110 self.
robot = builder(
112 package_dirs=[join(self.
model_path,
"../..")],
114 pin.JointModelFreeFlyer()
if self.
free_flyer else None
117 except AttributeError:
118 raise ImportError(
"Building SDF models require pinocchio >= 3.0.0")
132 if pin.WITH_HPP_FCL
and pin.WITH_HPP_FCL_BINDINGS:
134 self.
robot.collision_model.addAllCollisionPairs()
137 pin.removeCollisionPairs(
142 self.
robot.collision_data = self.
robot.collision_model.createData()
153 ub = self.
robot.model.upperPositionLimit
155 self.
robot.model.upperPositionLimit = ub
156 lb = self.
robot.model.lowerPositionLimit
158 self.
robot.model.lowerPositionLimit = lb
162 path =
"b1_description"
163 urdf_filename =
"b1.urdf"
164 urdf_subpath =
"urdf"
165 srdf_filename =
"b1.srdf"
166 ref_posture =
"standing"
171 path =
"go1_description"
172 urdf_filename =
"go1.urdf"
173 urdf_subpath =
"urdf"
174 srdf_filename =
"go1.srdf"
175 ref_posture =
"standing"
180 path =
"a1_description"
181 urdf_filename =
"a1.urdf"
182 urdf_subpath =
"urdf"
183 srdf_filename =
"a1.srdf"
184 ref_posture =
"standing"
189 path =
"z1_description"
190 urdf_filename =
"z1.urdf"
191 urdf_subpath =
"urdf"
192 srdf_filename =
"z1.srdf"
193 ref_posture =
"arm_up"
197 urdf_filename =
"b1-z1.urdf"
198 srdf_filename =
"b1-z1.srdf"
199 ref_posture =
"standing_with_arm_home"
203 path =
"anymal_b_simple_description"
204 urdf_filename =
"anymal.urdf"
205 srdf_filename =
"anymal.srdf"
206 ref_posture =
"standing"
211 path =
"anymal_c_simple_description"
212 urdf_subpath =
"urdf"
213 urdf_filename =
"anymal.urdf"
214 srdf_filename =
"anymal.srdf"
215 ref_posture =
"standing"
220 path =
"laikago_description"
221 urdf_subpath =
"urdf"
222 urdf_filename =
"laikago.urdf"
227 urdf_filename =
"anymal-kinova.urdf"
228 srdf_filename =
"anymal-kinova.srdf"
229 ref_posture =
"standing_with_arm_up"
233 path =
"baxter_description"
234 urdf_filename =
"baxter.urdf"
235 urdf_subpath =
"urdf"
239 path =
"cassie_description"
240 if tuple(int(i)
for i
in pin.__version__.split(
".")) > (2, 9, 1):
241 sdf_filename =
"cassie.sdf"
243 sdf_filename =
"cassie_v2.sdf"
244 sdf_subpath =
"robots"
245 srdf_filename =
"cassie_v2.srdf"
246 ref_posture =
"standing"
248 sdf_root_link_name =
"pelvis"
249 sdf_parent_guidance = [
254 "left-tarsus-spring-joint",
260 "right-tarsus-spring-joint",
267 urdf_filename =
"talos_reduced.urdf"
268 srdf_filename =
"talos.srdf"
270 has_rotor_parameters =
True
274 path =
"asr_twodof_description"
275 urdf_filename =
"TwoDofs.urdf"
276 urdf_subpath =
"urdf"
280 urdf_filename =
"talos_reduced_box.urdf"
284 urdf_filename =
"talos_full_v2.urdf"
288 urdf_filename =
"talos_full_v2_box.urdf"
292 urdf_filename =
"talos_left_arm.urdf"
298 super(TalosLegsLoader, self).
__init__(verbose=verbose)
300 m1 = self.
robot.model
302 for j, M, name, parent, Y
in zip(
303 m1.joints, m1.jointPlacements, m1.names, m1.parents, m1.inertias
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
311 m2.lowerPositionLimit[idx_q : idx_q + j.nq] = m1.lowerPositionLimit[
312 j.idx_q : j.idx_q + j.nq
314 m2.velocityLimit[idx_v : idx_v + j.nv] = m1.velocityLimit[
315 j.idx_v : j.idx_v + j.nv
317 m2.effortLimit[idx_v : idx_v + j.nv] = m1.effortLimit[
318 j.idx_v : j.idx_v + j.nv
321 m2.appendBodyToJoint(jid, Y, pin.SE3.Identity())
323 upperPos = m2.upperPositionLimit
325 m2.upperPositionLimit = upperPos
326 lowerPos = m2.lowerPositionLimit
328 m2.lowerPositionLimit = lowerPos
329 effort = m2.effortLimit
331 m2.effortLimit = effort
335 if f.parent < legMaxId:
338 g2 = pin.GeometryModel()
339 for g
in self.
robot.visual_model.geometryObjects:
340 if g.parentJoint < 14:
341 g2.addGeometryObject(g)
343 self.
robot.model = m2
344 self.
robot.data = m2.createData()
345 self.
robot.visual_model = g2
347 self.
robot.visual_data = pin.GeometryData(g2)
358 assert (m2.armature[:6] == 0.0).all()
364 path =
"hyq_description"
365 urdf_filename =
"hyq_no_sensors.urdf"
366 srdf_filename =
"hyq.srdf"
367 ref_posture =
"standing"
372 path =
"bolt_description"
373 urdf_filename =
"bolt.urdf"
374 srdf_filename =
"bolt.srdf"
375 ref_posture =
"standing"
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"
390 path =
"solo_description"
391 urdf_filename =
"solo.urdf"
392 srdf_filename =
"solo.srdf"
393 ref_posture =
"standing"
398 urdf_filename =
"solo12.urdf"
402 path =
"finger_edu_description"
403 urdf_filename =
"finger_edu.urdf"
404 srdf_filename =
"finger_edu.srdf"
405 ref_posture =
"hanging"
410 path =
"kinova_description"
411 urdf_filename =
"kinova.urdf"
412 srdf_filename =
"kinova.srdf"
413 ref_posture =
"arm_up"
417 path =
"tiago_description"
418 urdf_filename =
"tiago.urdf"
422 urdf_filename =
"tiago_dual.urdf"
426 urdf_filename =
"tiago_no_hand.urdf"
430 path =
"icub_description"
431 urdf_filename =
"icub.urdf"
432 srdf_filename =
"icub.srdf"
437 urdf_filename =
"icub_reduced.urdf"
441 path =
"panda_description"
442 urdf_filename =
"panda.urdf"
443 urdf_subpath =
"urdf"
444 srdf_filename =
"panda.srdf"
445 ref_posture =
"default"
449 path =
"allegro_hand_description"
450 urdf_filename =
"allegro_right_hand.urdf"
451 urdf_subpath =
"urdf"
455 path =
"allegro_hand_description"
456 urdf_filename =
"allegro_left_hand.urdf"
457 urdf_subpath =
"urdf"
461 path =
"ur_description"
462 urdf_filename =
"ur3_robot.urdf"
463 urdf_subpath =
"urdf"
468 urdf_filename =
"ur3_gripper.urdf"
469 srdf_filename =
"ur3_gripper.srdf"
473 urdf_filename =
"ur3_joint_limited_robot.urdf"
477 urdf_filename =
"ur5_robot.urdf"
478 srdf_filename =
"ur5.srdf"
482 urdf_filename =
"ur5_gripper.urdf"
483 srdf_filename =
"ur5_gripper.srdf"
487 urdf_filename =
"ur5_joint_limited_robot.urdf"
491 urdf_filename =
"ur10_robot.urdf"
495 urdf_filename =
"ur10_joint_limited_robot.urdf"
499 path =
"hector_description"
500 urdf_filename =
"quadrotor_base.urdf"
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"
515 path =
"double_pendulum_description"
516 urdf_filename =
"double_pendulum.urdf"
517 urdf_subpath =
"urdf"
521 urdf_filename =
"double_pendulum_continuous.urdf"
525 urdf_filename =
"double_pendulum_simple.urdf"
529 path =
"quadruped_description"
530 urdf_subpath =
"urdf"
531 urdf_filename =
"quadruped.urdf"
536 path =
"romeo_description"
537 urdf_filename =
"romeo.urdf"
538 urdf_subpath =
"urdf"
543 path =
"simple_humanoid_description"
544 urdf_subpath =
"urdf"
545 urdf_filename =
"simple_humanoid.urdf"
546 srdf_filename =
"simple_humanoid.srdf"
551 urdf_filename =
"simple_humanoid_classical.urdf"
552 srdf_filename =
"simple_humanoid_classical.srdf"
556 path =
"iris_description"
557 urdf_filename =
"iris_simple.urdf"
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,
580 "icub_reduced": ICubReducedLoader,
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,
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,
606 "ur3_gripper": UR3GripperLoader,
607 "ur3_limited": UR3LimitedLoader,
609 "ur5_gripper": UR5GripperLoader,
610 "ur5_limited": UR5LimitedLoader,
612 "ur10_limited": UR10LimitedLoader,
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()))
621 "Robot '%s' not found. Possible values are %s" % (name, robots)
623 inst = ROBOTS[name](verbose=verbose)
626 inst.robot.initViewer()
627 inst.robot.viz.loadViewerModel(rootNodeName=rootNodeName)
629 inst.robot.initViewer(loadModel=
True)
630 inst.robot.display(inst.robot.q0)
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
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