curobo.cuda_robot_model.usd_kinematics_parser module

class curobo.cuda_robot_model.usd_kinematics_parser.UsdKinematicsParser(usd_path, flip_joints=[], flip_joint_limits=[], usd_robot_root='robot', tensor_args=TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32), extra_links=None)

Bases: KinematicsParser

An experimental kinematics parser from USD. NOTE: A more complete solution will be available in a future release. Current implementation does not account for link geometry transformations after a joints.

Parameters:
  • usd_path (str) –

  • flip_joints (List[str]) –

  • flip_joint_limits (List[str]) –

  • usd_robot_root (str) –

  • tensor_args (TensorDeviceType) –

  • extra_links (Dict[str, LinkParams] | None) –

property robot_prim_root

Build a map of parent links to each link in the kinematic tree.

NOTE: Use this function to fill self._parent_map.

Get Link parameters from usd stage.

NOTE: 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) – flag to specify base link. Defaults to False.

Returns:

obtained link parameters.

Return type:

LinkParams

_get_joint_transform(prim)
Parameters:

prim (Prim) –

Get all link prims from the given joint prim.

Note

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 (Prim) –

Return type:

Tuple[Prim | None, Prim | None]