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_link_parent()¶
Build parent map for the robot.
- _get_joint_name(
- idx,
Get the name of the joint at the given index.
- Parameters:
idx – Index of the joint.
- Returns:
Name of the joint.
- Return type:
- _get_joint_limits(
- joint: Joint,
Get the limits of a joint.
This function converts continuous joints to revolute joints with limits [-6.28, 6.28].
- get_link_parameters(
- link_name: str,
- base=False,
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:
- add_absolute_path_to_link_meshes(
- mesh_dir: str = '',
Add absolute path to link meshes.
- Parameters:
mesh_dir – Absolute path to the directory containing link meshes.
- get_link_mesh(
- link_name: str,
Get mesh of a link.
- Parameters:
link_name – Name of the link.
- Returns:
Mesh of the link.
- Return type:
- property root_link: str¶
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:
- _get_from_extra_links(
- link_name: str,
Get link parameters for extra links.
- Parameters:
link_name – Name of the link.
- Returns:
Link parameters if found, else None.
- Return type:
- 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.