2 from os.path import dirname, exists, join
5 import pinocchio
as pin
8 pin.switchToNumpyArray()
12 source = dirname(dirname(dirname(__file__)))
15 dirname(dirname(dirname(source))),
"robots" 18 dirname(source),
"robots" 20 join(source,
"robots"),
23 from .path
import EXAMPLE_ROBOT_DATA_MODEL_DIR, EXAMPLE_ROBOT_DATA_SOURCE_DIR
26 EXAMPLE_ROBOT_DATA_MODEL_DIR
29 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,
"../..")],
103 root_joint=pin.JointModelFreeFlyer()
110 self.
robot = builder(
112 package_dirs=[join(self.
model_path,
"../..")],
113 root_joint=pin.JointModelFreeFlyer()
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()
151 ub = self.
robot.model.upperPositionLimit
153 self.
robot.model.upperPositionLimit = ub
154 lb = self.
robot.model.lowerPositionLimit
156 self.
robot.model.lowerPositionLimit = lb
160 path =
"a1_description" 161 urdf_filename =
"a1.urdf" 162 urdf_subpath =
"urdf" 163 srdf_filename =
"a1.srdf" 164 ref_posture =
"standing" 169 path =
"anymal_b_simple_description" 170 urdf_filename =
"anymal.urdf" 171 srdf_filename =
"anymal.srdf" 172 ref_posture =
"standing" 177 path =
"laikago_description" 178 urdf_subpath =
"urdf" 179 urdf_filename =
"laikago.urdf" 184 urdf_filename =
"anymal-kinova.urdf" 185 srdf_filename =
"anymal-kinova.srdf" 186 ref_posture =
"standing_with_arm_up" 190 path =
"baxter_description" 191 urdf_filename =
"baxter.urdf" 192 urdf_subpath =
"urdf" 196 path =
"cassie_description" 197 if tuple(int(i)
for i
in pin.__version__.split(
".")) > (2, 9, 1):
198 sdf_filename =
"cassie.sdf" 200 sdf_filename =
"cassie_v2.sdf" 201 sdf_subpath =
"robots" 202 srdf_filename =
"cassie_v2.srdf" 203 ref_posture =
"standing" 205 sdf_root_link_name =
"pelvis" 206 sdf_parent_guidance = [
211 "left-tarsus-spring-joint",
217 "right-tarsus-spring-joint",
224 urdf_filename =
"talos_reduced.urdf" 225 srdf_filename =
"talos.srdf" 227 has_rotor_parameters =
True 231 path =
"asr_twodof_description" 232 urdf_filename =
"TwoDofs.urdf" 233 urdf_subpath =
"urdf" 237 urdf_filename =
"talos_reduced_box.urdf" 241 urdf_filename =
"talos_full_v2.urdf" 245 urdf_filename =
"talos_full_v2_box.urdf" 249 urdf_filename =
"talos_left_arm.urdf" 255 super(TalosLegsLoader, self).
__init__()
257 m1 = self.
robot.model
259 for j, M, name, parent, Y
in zip(
260 m1.joints, m1.jointPlacements, m1.names, m1.parents, m1.inertias
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
268 m2.lowerPositionLimit[idx_q : idx_q + j.nq] = m1.lowerPositionLimit[
269 j.idx_q : j.idx_q + j.nq
271 m2.velocityLimit[idx_v : idx_v + j.nv] = m1.velocityLimit[
272 j.idx_v : j.idx_v + j.nv
274 m2.effortLimit[idx_v : idx_v + j.nv] = m1.effortLimit[
275 j.idx_v : j.idx_v + j.nv
278 m2.appendBodyToJoint(jid, Y, pin.SE3.Identity())
280 upperPos = m2.upperPositionLimit
282 m2.upperPositionLimit = upperPos
283 lowerPos = m2.lowerPositionLimit
285 m2.lowerPositionLimit = lowerPos
286 effort = m2.effortLimit
288 m2.effortLimit = effort
292 if f.parent < legMaxId:
295 g2 = pin.GeometryModel()
296 for g
in self.
robot.visual_model.geometryObjects:
297 if g.parentJoint < 14:
298 g2.addGeometryObject(g)
300 self.
robot.model = m2
301 self.
robot.data = m2.createData()
302 self.
robot.visual_model = g2
304 self.
robot.visual_data = pin.GeometryData(g2)
315 assert (m2.armature[:6] == 0.0).all()
321 path =
"hyq_description" 322 urdf_filename =
"hyq_no_sensors.urdf" 323 srdf_filename =
"hyq.srdf" 324 ref_posture =
"standing" 329 path =
"bolt_description" 330 urdf_filename =
"bolt.urdf" 331 srdf_filename =
"bolt.srdf" 332 ref_posture =
"standing" 337 path =
"solo_description" 338 urdf_filename =
"solo.urdf" 339 srdf_filename =
"solo.srdf" 340 ref_posture =
"standing" 345 urdf_filename =
"solo12.urdf" 349 path =
"finger_edu_description" 350 urdf_filename =
"finger_edu.urdf" 351 srdf_filename =
"finger_edu.srdf" 352 ref_posture =
"hanging" 357 path =
"kinova_description" 358 urdf_filename =
"kinova.urdf" 359 srdf_filename =
"kinova.srdf" 360 ref_posture =
"arm_up" 364 path =
"tiago_description" 365 urdf_filename =
"tiago.urdf" 369 urdf_filename =
"tiago_dual.urdf" 373 urdf_filename =
"tiago_no_hand.urdf" 377 path =
"icub_description" 378 urdf_filename =
"icub.urdf" 379 srdf_filename =
"icub.srdf" 384 urdf_filename =
"icub_reduced.urdf" 388 path =
"panda_description" 389 urdf_filename =
"panda.urdf" 390 urdf_subpath =
"urdf" 394 path =
"ur_description" 395 urdf_filename =
"ur3_robot.urdf" 396 urdf_subpath =
"urdf" 401 urdf_filename =
"ur3_gripper.urdf" 402 srdf_filename =
"ur3_gripper.srdf" 406 urdf_filename =
"ur3_joint_limited_robot.urdf" 410 urdf_filename =
"ur5_robot.urdf" 411 srdf_filename =
"ur5.srdf" 415 urdf_filename =
"ur5_gripper.urdf" 416 srdf_filename =
"ur5_gripper.srdf" 420 urdf_filename =
"ur5_joint_limited_robot.urdf" 424 urdf_filename =
"ur10_robot.urdf" 428 urdf_filename =
"ur10_joint_limited_robot.urdf" 432 path =
"hector_description" 433 urdf_filename =
"quadrotor_base.urdf" 438 path =
"double_pendulum_description" 439 urdf_filename =
"double_pendulum.urdf" 440 urdf_subpath =
"urdf" 444 urdf_filename =
"double_pendulum_continuous.urdf" 448 urdf_filename =
"double_pendulum_simple.urdf" 452 path =
"romeo_description" 453 urdf_filename =
"romeo.urdf" 454 urdf_subpath =
"urdf" 459 path =
"simple_humanoid_description" 460 urdf_subpath =
"urdf" 461 urdf_filename =
"simple_humanoid.urdf" 462 srdf_filename =
"simple_humanoid.srdf" 467 urdf_filename =
"simple_humanoid_classical.urdf" 468 srdf_filename =
"simple_humanoid_classical.srdf" 472 path =
"iris_description" 473 urdf_filename =
"iris_simple.urdf" 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,
490 "icub_reduced": ICubReducedLoader,
492 "kinova": KinovaLoader,
493 "laikago": LaikagoLoader,
494 "panda": PandaLoader,
495 "romeo": RomeoLoader,
496 "simple_humanoid": SimpleHumanoidLoader,
497 "simple_humanoid_classical": SimpleHumanoidClassicalLoader,
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,
512 "ur3_gripper": UR3GripperLoader,
513 "ur3_limited": UR3LimitedLoader,
515 "ur5_gripper": UR5GripperLoader,
516 "ur5_limited": UR5LimitedLoader,
518 "ur10_limited": UR10LimitedLoader,
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()))
527 "Robot '%s' not found. Possible values are %s" % (name, robots)
529 inst = ROBOTS[name]()
532 inst.robot.initViewer()
533 inst.robot.viz.loadViewerModel(rootNodeName=rootNodeName)
535 inst.robot.initViewer(loadModel=
True)
536 inst.robot.display(inst.robot.q0)
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
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
string sdf_root_link_name
def addFreeFlyerJointLimits(self)
bool has_rotor_parameters
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...