blenderproc.python.loader.URDFLoader module

Loading URDF files.

blenderproc.python.loader.URDFLoader.create_bone(armature, joint_tree, all_joint_trees, parent_bone_name=None, create_recursive=True, parent_origin=None, fk_offset=None, ik_offset=None)[source]

Creates deform, fk and ik bone for a specific joint. Can loop recursively through the child(ren).

Parameters:
  • armature (Armature) – The armature which encapsulates all bones.

  • joint_tree (urdfpy.Joint) – The urdf definition for the joint.

  • all_joint_trees (List[urdfpy.Joint]) – List of urdf definitions for all joints.

  • parent_bone_name (Optional[str]) – Name of the parent bone.

  • create_recursive (bool) – Whether to recursively create bones for the child(ren) of the link.

  • parent_origin (Optional[Matrix]) – Pose of the parent.

  • fk_offset (Union[List[float], Vector, array]) – Offset between fk bone chain and link bone chain. This does not have any effect on the transformations, but can be useful for visualization in blender.

  • ik_offset (Union[List[float], Vector, array]) – Offset between fk bone chain and link bone chain. Effects on the transformation (e.g. urdf_object.set_location_ik()) are being handled internally. Useful for visualization in blender.

Returns the joint which is the parent of a specific link.

Parameters:
  • link_name (str) – Name of the link.

  • joint_trees (List[urdfpy.Joint]) – List of urdfpy.Joint objects.

Return type:

Optional[urdfpy.Joint]

Returns:

List of urdfpy.Joint objects, or None if no joint is defined as parent for the respective link.

Returns a list of joints which have a specific link as parent.

Parameters:
  • link_name (str) – Name of the link.

  • joint_trees (List[urdfpy.Joint]) – List of urdfpy.Joint objects.

Return type:

List[urdfpy.Joint]

Returns:

List of urdfpy.Joint objects.

blenderproc.python.loader.URDFLoader.get_size_from_geometry(geometry)[source]

Helper to derive the link size from the largest geometric element.

Parameters:

geometry (urdfpy.Geometry) – The urdf representation of the geometric element.

Return type:

Optional[float]

Returns:

A single float representing the link’s size.

blenderproc.python.loader.URDFLoader.load_geometry(geometry_tree, urdf_path=None)[source]

Loads a geometric element from an urdf tree.

Parameters:
  • geometry_tree (urdfpy.Geometry) – The urdf representation of the geometric element.

  • urdf_path (Optional[str]) – Optional path of the urdf file for relative geometry files.

Return type:

MeshObject

Returns:

The respective MeshObject.

blenderproc.python.loader.URDFLoader.load_inertial(inertial_tree, name)[source]

Loads an inertial element from an urdf tree.

Parameters:
  • inertial_tree (urdfpy.Inertial) – The urdf representation of the inertial element.

  • name (str) – Name if the inertial element.

Return type:

Inertial

Returns:

The respective Inertial object.

Loads links and their visual, collision and inertial objects from a list of urdfpy.Link objects.

Parameters:
  • link_trees (List[urdfpy.Link]) – List of urdf definitions for all links.

  • joint_trees (List[urdfpy.Joint]) – List of urdf definitions for all joints.

  • armature (Armature) – The armature which encapsulates all bones.

  • urdf_path (str) – Path to the URDF file.

Return type:

List[Link]

Returns:

List of links.

blenderproc.python.loader.URDFLoader.load_urdf(urdf_file, weight_distribution='rigid', fk_offset=None, ik_offset=None)[source]

Loads an urdf object from an URDF file.

Parameters:
  • urdf_file (str) – Path to the URDF file.

  • weight_distribution (str) – One of [‘envelope’, ‘automatic’, ‘rigid’]. For more information please see https://docs.blender.org/manual/en/latest/animation/armatures/skinning/parenting.html.

  • fk_offset (Union[List[float], Vector, array, None]) – Offset between fk (forward kinematic) bone chain and link bone chain. This does not have any effect on the transformations, but can be useful for visualization in blender.

  • ik_offset (Union[List[float], Vector, array, None]) – Offset between ik (inverse kinematic) bone chain and link bone chain. Effects on the transformation (e.g. urdf_object.set_location_ik()) are being handled internally. Useful for visualization in blender.

Return type:

URDFObject

Returns:

URDF object instance.

blenderproc.python.loader.URDFLoader.load_visual_collision_obj(viscol_tree, name, urdf_path=None)[source]

Loads a visual / collision element from an urdf tree.

Parameters:
  • viscol_tree (Union[urdfpy.Visual, urdfpy.Collision]) – The urdf representation of the visual / collision element.

  • name (str) – Name of the visual / collision element.

  • urdf_path (Optional[str]) – Optional path of the urdf file for relative geometry files.

Return type:

MeshObject

Returns:

The respective MeshObject.

blenderproc.python.loader.URDFLoader.propagate_pose(links, joint_tree, joint_trees, armature, recursive=True)[source]

Loads links and their visual, collision and inertial objects from a list of urdfpy.Link objects.

Parameters:
  • links (List[Link]) – List of links.

  • joint_tree (urdfpy.Joint) – The urdf definition for the joint.

  • joint_trees (List[urdfpy.Joint]) – List of urdf definitions for all joints.

  • armature (Armature) – The armature which encapsulates all bones.

  • recursive (bool) – Whether to recursively create bones for the child(ren) of the link.