3 from os.path import dirname, exists, join
6 import pinocchio
as pin
9 pin.switchToNumpyArray()
13 return "`%s` is deprecated. Please use `load('%s')`" % (deprecated, key)
17 source = dirname(dirname(dirname(__file__)))
19 join(dirname(dirname(dirname(source))),
'robots'),
20 join(dirname(source),
'robots'),
21 join(source,
'robots')
24 from .path
import EXAMPLE_ROBOT_DATA_MODEL_DIR, EXAMPLE_ROBOT_DATA_SOURCE_DIR
25 paths.append(EXAMPLE_ROBOT_DATA_MODEL_DIR)
26 paths.append(EXAMPLE_ROBOT_DATA_SOURCE_DIR)
29 paths += [join(p,
'../../../share/example-robot-data/robots')
for p
in sys.path]
31 if exists(join(path, subpath.strip(
'/'))):
33 print(
"using %s as modelPath" % path)
35 raise IOError(
'%s not found' % subpath)
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()
53 urdf_subpath =
'robots' 55 ref_posture =
'half_sitting' 56 has_rotor_parameters =
False 65 pin.JointModelFreeFlyer()
if self.
free_flyer else None)
79 ub = self.robot.model.upperPositionLimit
81 self.robot.model.upperPositionLimit = ub
82 lb = self.robot.model.lowerPositionLimit
84 self.robot.model.lowerPositionLimit = lb
88 warnings.warn(
"`q0` is deprecated. Please use `robot.q0`", FutureWarning, 2)
93 path =
'anymal_b_simple_description' 94 urdf_filename =
"anymal.urdf" 95 srdf_filename =
"anymal.srdf" 96 ref_posture =
"standing" 101 urdf_filename =
"anymal-kinova.urdf" 102 srdf_filename =
"anymal-kinova.srdf" 103 ref_posture =
"standing_with_arm_up" 108 warnings.warn(
_depr_msg(
'loadANYmal(kinova)',
'anymal_kinova'), FutureWarning, 2)
109 loader = ANYmalKinovaLoader
111 warnings.warn(
_depr_msg(
'loadANYmal()',
'anymal'), FutureWarning, 2)
112 loader = ANYmalLoader
118 urdf_filename =
"talos_reduced.urdf" 119 srdf_filename =
"talos.srdf" 124 urdf_filename =
"talos_reduced_box.urdf" 128 urdf_filename =
"talos_full_v2.urdf" 132 urdf_filename =
"talos_full_v2_box.urdf" 136 urdf_filename =
"talos_left_arm.urdf" 142 super(TalosLegsLoader, self).
__init__()
144 m1 = self.robot.model
146 for j, M, name, parent, Y
in zip(m1.joints, m1.jointPlacements, m1.names, m1.parents, m1.inertias):
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 +
154 lowerPos[m2.joints[jid].idx_q:m2.joints[jid].idx_q + j.nq] = m1.lowerPositionLimit[j.idx_q:j.idx_q +
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
161 m2.appendBodyToJoint(jid, Y, pin.SE3.Identity())
163 upperPos = m2.upperPositionLimit
165 m2.upperPositionLimit = upperPos
166 lowerPos = m2.lowerPositionLimit
168 m2.lowerPositionLimit = lowerPos
169 effort = m2.effortLimit
171 m2.effortLimit = effort
175 if f.parent < legMaxId:
178 g2 = pin.GeometryModel()
179 for g
in self.robot.visual_model.geometryObjects:
180 if g.parentJoint < 14:
181 g2.addGeometryObject(g)
183 self.robot.model = m2
184 self.robot.data = m2.createData()
185 self.robot.visual_model = g2
187 self.robot.visual_data = pin.GeometryData(g2)
193 assert (m2.armature[:6] == 0.).all()
198 def loadTalos(legs=False, arm=False, full=False, box=False):
200 warnings.warn(
_depr_msg(
'loadTalos(legs)',
'talos_legs'), FutureWarning, 2)
201 loader = TalosLegsLoader
203 warnings.warn(
_depr_msg(
'loadTalos(arm)',
'talos_arm'), FutureWarning, 2)
204 loader = TalosArmLoader
207 warnings.warn(
_depr_msg(
'loadTalos(full, box)',
'talos_full_box'), FutureWarning, 2)
208 loader = TalosFullBoxLoader
210 warnings.warn(
_depr_msg(
'loadTalos(full)',
'talos_full'), FutureWarning, 2)
211 loader = TalosFullLoader
214 warnings.warn(
_depr_msg(
'loadTalos(box)',
'talos_box'), FutureWarning, 2)
215 loader = TalosBoxLoader
217 warnings.warn(
_depr_msg(
'loadTalos()',
'talos'), FutureWarning, 2)
223 warnings.warn(
_depr_msg(
'loadTalosLegs()',
'talos_legs'), FutureWarning, 2)
228 warnings.warn(
_depr_msg(
'loadTalosArm()',
'talos_arm'), FutureWarning, 2)
233 path =
"hyq_description" 234 urdf_filename =
"hyq_no_sensors.urdf" 235 srdf_filename =
"hyq.srdf" 236 ref_posture =
"standing" 241 warnings.warn(
_depr_msg(
'loadHyQ()',
'hyq'), FutureWarning, 2)
246 path =
'solo_description' 247 urdf_filename =
"solo.urdf" 248 srdf_filename =
"solo.srdf" 249 ref_posture =
"standing" 254 urdf_filename =
"solo12.urdf" 258 warnings.warn(
_depr_msg(
'loadSolo()',
'solo'), FutureWarning, 2)
259 loader = SoloLoader
if solo
else Solo12Loader
264 path =
"kinova_description" 265 urdf_filename =
"kinova.urdf" 266 srdf_filename =
"kinova.srdf" 267 ref_posture =
"arm_up" 271 warnings.warn(
_depr_msg(
'loadKinova()',
'kinova'), FutureWarning, 2)
276 path =
"tiago_description" 277 urdf_filename =
"tiago.urdf" 281 urdf_filename =
"tiago_no_hand.urdf" 286 warnings.warn(
_depr_msg(
'loadTiago()',
'tiago'), FutureWarning, 2)
289 warnings.warn(
_depr_msg(
'loadTiago(hand=False)',
'tiago_no_hand'), FutureWarning, 2)
290 loader = TiagoNoHandLoader
295 warnings.warn(
_depr_msg(
'loadTiagoNoHand()',
'tiago_no_hand'), FutureWarning, 2)
300 path =
"icub_description" 301 urdf_filename =
"icub.urdf" 302 srdf_filename =
"icub.srdf" 307 urdf_filename =
"icub_reduced.urdf" 312 warnings.warn(
_depr_msg(
'loadICub()',
'icub_reduced'), FutureWarning, 2)
313 loader = ICubReducedLoader
315 warnings.warn(
_depr_msg(
'loadICub(reduced=False)',
'icub'), FutureWarning, 2)
321 path =
"panda_description" 322 urdf_filename =
"panda.urdf" 323 urdf_subpath =
"urdf" 327 warnings.warn(
_depr_msg(
'loadPanda()',
'panda'), FutureWarning, 2)
332 path =
"ur_description" 333 urdf_filename =
"ur3_robot.urdf" 334 urdf_subpath =
"urdf" 339 urdf_filename =
"ur3_gripper.urdf" 340 srdf_filename =
"ur3_gripper.srdf" 344 urdf_filename =
"ur3_joint_limited_robot.urdf" 348 urdf_filename =
"ur5_robot.urdf" 349 srdf_filename =
"ur5.srdf" 353 urdf_filename =
"ur5_gripper.urdf" 354 srdf_filename =
"ur5_gripper.srdf" 358 urdf_filename =
"ur5_joint_limited_robot.urdf" 362 urdf_filename =
"ur10_robot.urdf" 366 urdf_filename =
"ur10_joint_limited_robot.urdf" 369 def loadUR(robot=5, limited=False, gripper=False):
372 warnings.warn(
_depr_msg(
'loadUr(3, limited)',
'ur3_limited'), FutureWarning, 2)
373 loader = UR3LimitedLoader
375 warnings.warn(
_depr_msg(
'loadUr(3, gripper)',
'ur3_gripper'), FutureWarning, 2)
376 loader = UR3GripperLoader
378 warnings.warn(
_depr_msg(
'loadUr(3)',
'ur3'), FutureWarning, 2)
382 warnings.warn(
_depr_msg(
'loadUr(limited)',
'ur5_limited'), FutureWarning, 2)
383 loader = UR5LimitedLoader
385 warnings.warn(
_depr_msg(
'loadUr(gripper)',
'ur5_gripper'), FutureWarning, 2)
386 loader = UR5GripperLoader
388 warnings.warn(
_depr_msg(
'loadUr()',
'ur5'), FutureWarning, 2)
392 warnings.warn(
_depr_msg(
'loadUr(10, limited)',
'ur10_limited'), FutureWarning, 2)
393 loader = UR10LimitedLoader
395 warnings.warn(
_depr_msg(
'loadUr(10)',
'ur10'), FutureWarning, 2)
401 path =
"hector_description" 402 urdf_filename =
"quadrotor_base.urdf" 407 warnings.warn(
_depr_msg(
'loadHector()',
'hector'), FutureWarning, 2)
412 path =
"double_pendulum_description" 413 urdf_filename =
"double_pendulum.urdf" 414 urdf_subpath =
"urdf" 418 warnings.warn(
_depr_msg(
'loadDoublePendulum()',
'double_pendulum'), FutureWarning, 2)
423 path =
"romeo_description" 424 urdf_filename =
"romeo.urdf" 425 urdf_subpath =
"urdf" 430 warnings.warn(
_depr_msg(
'loadRomeo()',
'romeo'), FutureWarning, 2)
435 path =
'simple_humanoid_description' 436 urdf_subpath =
'urdf' 437 urdf_filename =
'simple_humanoid.urdf' 438 srdf_filename =
'simple_humanoid.srdf' 443 urdf_filename =
'simple_humanoid_classical.urdf' 444 srdf_filename =
'simple_humanoid_classical.srdf' 448 path =
"iris_description" 449 urdf_filename =
"iris_simple.urdf" 454 warnings.warn(
_depr_msg(
'loadIris()',
'iris'), FutureWarning, 2)
459 'anymal': ANYmalLoader,
460 'anymal_kinova': ANYmalKinovaLoader,
461 'double_pendulum': DoublePendulumLoader,
462 'hector': HectorLoader,
465 'icub_reduced': ICubReducedLoader,
467 'kinova': KinovaLoader,
468 'panda': PandaLoader,
469 'romeo': RomeoLoader,
470 'simple_humanoid': SimpleHumanoidLoader,
471 'simple_humanoid_classical': SimpleHumanoidClassicalLoader,
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,
483 'ur3_gripper': UR3GripperLoader,
484 'ur3_limited': UR3LimitedLoader,
486 'ur5_gripper': UR5GripperLoader,
487 'ur5_limited': UR5LimitedLoader,
489 'ur10_limited': UR10LimitedLoader,
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]()
501 inst.robot.initViewer()
502 inst.robot.viz.loadViewerModel(rootNodeName=rootNodeName)
504 inst.robot.initViewer(loadModel=
True)
505 inst.robot.display(inst.robot.q0)
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
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 loadANYmal(withArm=None)
def addFreeFlyerJointLimits(self)
def load_full(name, display=False, rootNodeName='')
def loadICub(reduced=True)
bool has_rotor_parameters
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...