curobo.robot_parser module

Robot kinematic parsers.

Parsers turn robot description files into the link/joint data structures used by curobo.kinematics.Kinematics. Most users do not call parsers directly — the high-level builders in curobo.robot_builder consume them internally. This module is useful when you need direct access to the parsed representation, e.g. for inspecting link meshes or joint limits.

Example

from curobo.robot_parser import UrdfRobotParser

parser = UrdfRobotParser("robot.urdf", mesh_root="assets/")
link_names = parser.get_link_names()
mesh = parser.get_link_mesh(link_names[0])
class UrdfRobotParser(
urdf_path,
load_meshes=False,
mesh_root='',
extra_links=None,
build_scene_graph=False,
)

Bases: curobo._src.robot.parser.parser_base.RobotParser

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 (bool) – Load meshes for links from the URDF file.

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

  • extra_links (Optional[Dict[str, LinkParams]]) – Extra links to add to the kinematic tree.

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

__init__(
urdf_path,
load_meshes=False,
mesh_root='',
extra_links=None,
build_scene_graph=False,
)

Initialize instance with URDF file path.

Parameters:
  • urdf_path – Path to the URDF file.

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

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

  • extra_links (Optional[Dict[str, LinkParams]]) – Extra links to add to the kinematic tree.

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

Return type:

None

Build parent map for the robot.

Get parameters of a link in the kinematic tree.

Parameters:
  • link_name (str) – 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 (str) – Absolute path to the directory containing link meshes.

get_urdf_string()

Get the contents of URDF as a string.

Return type:

str

Get geometry of a link.

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

  • use_collision_mesh (bool)

Returns:

List of geometry of the link.

Return type:

List[Obstacle]

Get mesh of a link.

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

  • use_collision_mesh (bool)

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 names of all links in the kinematic tree from the URDF.

Returns:

List of link names.

Return type:

List[str]

get_joint_names_from_urdf()

Get names of all joints in the kinematic tree from the URDF.

Returns:

List of joint names.

Return type:

List[str]