curobo.cuda_robot_model.urdf_kinematics_parser module

Parses Kinematics from an URDF file that describes the kinematic tree of a robot.

class UrdfKinematicsParser(
urdf_path,
load_meshes: bool = False,
mesh_root: str = '',
extra_links: Dict[str, LinkParams] | None = None,
build_scene_graph: bool = False,
)

Bases: KinematicsParser

Parses Kinematics from an URDF file and provides access to the kinematic tree.

Initialize instance with URDF file path.

Parameters:
  • urdf_path – Path to the URDF file.

  • load_meshes – Load meshes for links from the URDF file.

  • mesh_root – Absolute path to the directory where link meshes are stored.

  • extra_links – Extra links to add to the kinematic tree.

  • build_scene_graph – Build scene graph for the robot. Set this to True if you want to determine the root link of the robot.

Build parent map for the robot.

_get_joint_name(
idx,
) str

Get the name of the joint at the given index.

Parameters:

idx – Index of the joint.

Returns:

Name of the joint.

Return type:

str

_get_joint_limits(
joint: Joint,
) Tuple[Dict[str, float], str]

Get the limits of a joint.

This function converts continuous joints to revolute joints with limits [-6.28, 6.28].

Parameters:

joint – Instance of the joint.

Returns:

Limits of the joint and the type of the joint

(revolute or prismatic).

Return type:

Tuple[Dict[str, float], str]

Get parameters of a link in the kinematic tree.

Parameters:
  • link_name – Name of the link.

  • base – Is this the base link of the robot?

Returns:

Parameters of the link.

Return type:

LinkParams

Add absolute path to link meshes.

Parameters:

mesh_dir – Absolute path to the directory containing link meshes.

get_urdf_string() str

Get the contents of URDF as a string.

Get mesh of a link.

Parameters:

link_name – Name of the link.

Returns:

Mesh of the link.

Return type:

Mesh

Returns the name of the base link of the robot.

Only available when the URDF is loaded with build_scene_graph=True.

Returns:

Name of the base link.

Return type:

str

Get link parameters for extra links.

Parameters:

link_name – Name of the link.

Returns:

Link parameters if found, else None.

Return type:

LinkParams

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.

_parent_map

Parent link for all link in the kinematic tree.