URDF

class urdfpy.URDF(name, links, joints=None, transmissions=None, materials=None, other_xml=None)[source]

Bases: urdfpy.URDFType

The top-level URDF specification.

The URDF encapsulates an articulated object, such as a robot or a gripper. It is made of links and joints that tie them together and define their relative motions.

Parameters:
  • name (str) – The name of the URDF.
  • links (list of Link) – The links of the URDF.
  • joints (list of Joint, optional) – The joints of the URDF.
  • transmissions (list of Transmission, optional) – The transmissions of the URDF.
  • materials (list of Material, optional) – The materials for the URDF.
  • other_xml (str, optional) – A string containing any extra XML for extensions.

Attributes Summary

actuated_joints The joints that are independently actuated.
base_link The base link for the URDF.
end_links The end links for the URDF.
joint_limit_cfgs The lower-bound and upper-bound joint configuration maps.
joint_map Map from joint names to the joints themselves.
joints The links of the URDF.
link_map Map from link names to the links themselves.
links The links of the URDF.
material_map Map from material names to the materials themselves.
materials The materials of the URDF.
name The name of the URDF.
other_xml Any extra XML that belongs with the URDF.
transmission_map Map from transmission names to the transmissions themselves.
transmissions The transmissions of the URDF.

Methods Summary

animate([cfg_trajectory, loop_time, …]) Animate the URDF through a configuration trajectory.
collision_geometry_fk([cfg, links]) Computes the poses of the URDF’s collision geometries using fk.
collision_trimesh_fk([cfg, links]) Computes the poses of the URDF’s collision trimeshes using fk.
link_fk([cfg, links]) Computes the poses of the URDF’s links via forward kinematics.
load(file_obj) Load a URDF from a file.
save(file_obj) Save this URDF to a file.
show([cfg, use_collision]) Visualize the URDF in a given configuration.
visual_geometry_fk([cfg, links]) Computes the poses of the URDF’s visual geometries using fk.
visual_trimesh_fk([cfg, links]) Computes the poses of the URDF’s visual trimeshes using fk.

Attributes Documentation

actuated_joints

The joints that are independently actuated.

This excludes mimic joints and fixed joints.

Type:list of Joint

The base link for the URDF.

The base link is the single link that has no parent.

Type:Link

The end links for the URDF.

The end links are the links that have no children.

Type:list of Link
joint_limit_cfgs

The lower-bound and upper-bound joint configuration maps.

The first map is the lower-bound map, which maps limited joints to their lower joint limits. The second map is the upper-bound map, which maps limited joints to their upper joint limits.

Type:tuple of dict
joint_map

Map from joint names to the joints themselves.

This returns a copy of the joint map which cannot be edited directly. If you want to add or remove joints, use the appropriate functions.

Type:dict
joints

The links of the URDF.

This returns a copy of the joints array which cannot be edited directly. If you want to add or remove joints, use the appropriate functions.

Type:list of Joint

Map from link names to the links themselves.

This returns a copy of the link map which cannot be edited directly. If you want to add or remove links, use the appropriate functions.

Type:dict

The links of the URDF.

This returns a copy of the links array which cannot be edited directly. If you want to add or remove links, use the appropriate functions.

Type:list of Link
material_map

Map from material names to the materials themselves.

This returns a copy of the material map which cannot be edited directly. If you want to add or remove materials, use the appropriate functions.

Type:dict
materials

The materials of the URDF.

This returns a copy of the materials array which cannot be edited directly. If you want to add or remove materials, use the appropriate functions.

Type:list of Material
name

The name of the URDF.

Type:str
other_xml

Any extra XML that belongs with the URDF.

Type:str
transmission_map

Map from transmission names to the transmissions themselves.

This returns a copy of the transmission map which cannot be edited directly. If you want to add or remove transmissions, use the appropriate functions.

Type:dict
transmissions

The transmissions of the URDF.

This returns a copy of the transmissions array which cannot be edited directly. If you want to add or remove transmissions, use the appropriate functions.

Type:list of Transmission

Methods Documentation

animate(cfg_trajectory=None, loop_time=3.0, use_collision=False)[source]

Animate the URDF through a configuration trajectory.

Parameters:
  • cfg_trajectory (dict) – A map from joints or joint names to lists of configuration values for each joint along the trajectory. If not specified, all joints will articulate from limit to limit. The trajectory steps are assumed to be equally spaced out in time.
  • loop_time (float) – The time to loop the animation for, in seconds. The trajectory will play fowards and backwards during this time, ending at the inital configuration.
  • use_collision (bool) – If True, the collision geometry is visualized instead of the visual geometry.

Examples

You can run this without specifying a cfg_trajectory to view the full articulation of the URDF

>>> robot = URDF.load('ur5.urdf')
>>> robot.animate()
../_images/ur5.gif
>>> ct = {'shoulder_pan_joint': [0.0, 2 * np.pi]}
>>> robot.animate(cfg_trajectory=ct)
../_images/ur5_shoulder.gif
>>> ct = {
...    'shoulder_pan_joint' : [-np.pi / 4, np.pi / 4],
...    'shoulder_lift_joint' : [0.0, -np.pi / 2.0],
...    'elbow_joint' : [0.0, np.pi / 2.0]
... }
>>> robot.animate(cfg_trajectory=ct)
../_images/ur5_three_joints.gif
collision_geometry_fk(cfg=None, links=None)[source]

Computes the poses of the URDF’s collision geometries using fk.

Parameters:
  • cfg (dict) – A map from joints or joint names to configuration values for each joint. If not specified, all joints are assumed to be in their default configurations.
  • links (list of str or list of Link) – The links or names of links to perform forward kinematics on. Only geometries from these links will be in the returned map. If not specified, all links are returned.
Returns:

fk – A map from Geometry objects that are part of the collision elements of the specified links to the 4x4 homogenous transform matrices that position them relative to the base link’s frame.

Return type:

dict

collision_trimesh_fk(cfg=None, links=None)[source]

Computes the poses of the URDF’s collision trimeshes using fk.

Parameters:
  • cfg (dict) – A map from joints or joint names to configuration values for each joint. If not specified, all joints are assumed to be in their default configurations.
  • links (list of str or list of Link) – The links or names of links to perform forward kinematics on. Only trimeshes from these links will be in the returned map. If not specified, all links are returned.
Returns:

fk – A map from Trimesh objects that are part of the collision geometry of the specified links to the 4x4 homogenous transform matrices that position them relative to the base link’s frame.

Return type:

dict

Computes the poses of the URDF’s links via forward kinematics.

Parameters:
  • cfg (dict) – A map from joints or joint names to configuration values for each joint. If not specified, all joints are assumed to be in their default configurations.
  • links (list of str or list of Link) – The links or names of links to perform forward kinematics on. Only these links will be in the returned map. If not specified, all links are returned.
Returns:

fk – A map from links to 4x4 homogenous transform matrices that position them relative to the base link’s frame.

Return type:

dict

static load(file_obj)[source]

Load a URDF from a file.

Parameters:file_obj (str or file-like object) – The file to load the URDF from. Should be the path to the .urdf XML file. Any paths in the URDF should be specified as relative paths to the .urdf file instead of as ROS resources.
Returns:urdf – The parsed URDF.
Return type:URDF
save(file_obj)[source]

Save this URDF to a file.

Parameters:file_obj (str or file-like object) – The file to save the URDF to. Should be the path to the .urdf XML file. Any paths in the URDF should be specified as relative paths to the .urdf file instead of as ROS resources.
Returns:urdf – The parsed URDF.
Return type:URDF
show(cfg=None, use_collision=False)[source]

Visualize the URDF in a given configuration.

Parameters:
  • cfg (dict) – A map from joints or joint names to configuration values for each joint. If not specified, all joints are assumed to be in their default configurations.
  • use_collision (bool) – If True, the collision geometry is visualized instead of the visual geometry.
visual_geometry_fk(cfg=None, links=None)[source]

Computes the poses of the URDF’s visual geometries using fk.

Parameters:
  • cfg (dict) – A map from joints or joint names to configuration values for each joint. If not specified, all joints are assumed to be in their default configurations.
  • links (list of str or list of Link) – The links or names of links to perform forward kinematics on. Only geometries from these links will be in the returned map. If not specified, all links are returned.
Returns:

fk – A map from Geometry objects that are part of the visual elements of the specified links to the 4x4 homogenous transform matrices that position them relative to the base link’s frame.

Return type:

dict

visual_trimesh_fk(cfg=None, links=None)[source]

Computes the poses of the URDF’s visual trimeshes using fk.

Parameters:
  • cfg (dict) – A map from joints or joint names to configuration values for each joint. If not specified, all joints are assumed to be in their default configurations.
  • links (list of str or list of Link) – The links or names of links to perform forward kinematics on. Only trimeshes from these links will be in the returned map. If not specified, all links are returned.
Returns:

fk – A map from Trimesh objects that are part of the visual geometry of the specified links to the 4x4 homogenous transform matrices that position them relative to the base link’s frame.

Return type:

dict