curobo.cuda_robot_model.usd_kinematics_parser module

An experimental kinematics parser that reads the robot from a USD file or stage.

Basic loading of simple robots should work but more complex robots may not be supported. E.g., mimic joints cannot be parsed correctly. Use the URDF parser (UrdfKinematicsParser) for more complex robots.

class UsdKinematicsParser(
usd_path: str,
flip_joints: List[str] = [],
flip_joint_limits: List[str] = [],
usd_robot_root: str = 'robot',
tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
extra_links: Dict[str, LinkParams] | None = None,
)

Bases: KinematicsParser

An experimental kinematics parser from USD.

Current implementation does not account for link geometry transformations after a joints. Also, cannot read mimic joints.

Initialize instance with USD file path.

Parameters:
  • usd_path – path to usd reference. This will opened as a Usd Stage.

  • flip_joints – list of joint names to flip axis. This is required as current implementation does not read transformations from joint to link correctly.

  • flip_joint_limits – list of joint names to flip joint limits.

  • usd_robot_root – Root prim of the robot in the Usd Stage.

  • tensor_args – Device and floating point precision for tensors.

  • extra_links – Additional links to add to the robot kinematics structure.

property robot_prim_root

Root prim of the robot in the Usd Stage.

Build a dictionary containing parent link for each link in the robot.

Get Link parameters from usd stage.

USD kinematics “X” axis joints map to “Z” in URDF. Specifically, uniform token physics:axis = “X” value only matches “Z” in URDF. This is because of usd files assuming Y axis as up while urdf files assume Z axis as up.

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

  • base (bool, optional) – Is this the base link of the robot?

Returns:

Obtained link parameters.

Return type:

LinkParams

_get_joint_transform(
prim: Prim,
) Pose

Get pose of link from joint prim.

Parameters:

prim – joint prim in the usd stage.

Returns:

pose of the link from joint origin.

Return type:

Pose

Get link parameters for extra links.

Parameters:

link_name – Name of the link.

Returns:

Link parameters if found, else None.

Return type:

LinkParams

Add absolute path to link meshes.

Parameters:

mesh_dir – Absolute path to the directory containing link meshes.

get_chain(
base_link: str,
ee_link: str,
) List[str]

Get list of links attaching ee_link to base_link.

Parameters:
  • base_link (str) – Name of base link.

  • ee_link (str) – Name of end-effector link.

Returns:

List of link names starting from base_link to ee_link.

Return type:

List[str]

get_controlled_joint_names() List[str]

Get names of all controlled joints in the robot.

Returns:

Names of all controlled joints in the robot.

Get mesh of a link.

Parameters:

link_name – Name of the link.

Returns:

Mesh of the link.

Return type:

Mesh

_parent_map

Parent link for all link in the kinematic tree.

Get all link prims from the given joint prim.

This assumes that the body0_rel_targets and body1_rel_targets are configured such that the parent link is specified in body0_rel_targets and the child links is specified in body1_rel_targets.

Parameters:

prim – joint prim in the usd stage.

Returns:

parent link prim and child link prim.

Return type:

Tuple[Optional[Usd.Prim], Optional[Usd.Prim]]