urdf_utils

mplib.urdf_utils.compute_default_collisions(
robot: ArticulatedModel,
*,
num_samples=100000,
verbose=False,
) str[source]

Compute default collision pairs for generating SRDF.

This function mimics MoveIt2’s moveit_setup::srdf_setup::computeDefaultCollisions()

Reference: https://moveit.picknik.ai/main/api/html/namespacemoveit__setup_1_1srdf__setup.html#a2812f73b447d838cd7dba1b0ee1a0c95

Parameters:
  • robot – an ArticulatedModel

  • num_samples – number of samples to find the link that will always collide

  • verbose – print debug info

Returns:

SRDF content as an XML string

mplib.urdf_utils.replace_urdf_package_keyword(
urdf_path: str | Path,
new_package_keyword: str = '',
) Path[source]

Some ROS URDF files use package:// keyword to refer the package dir. Replace it with the given string (default is empty)

Parameters:
  • urdf_path – Path to a Unified Robot Description Format file.

  • new_package_keyword – the string to replace package:// keyword

Returns:

Path to the modified URDF file

mplib.urdf_utils.generate_srdf(
urdf_path: str | Path,
new_package_keyword: str = '',
*,
num_samples=100000,
verbose=False,
) Path[source]

Generate SRDF from URDF similar to MoveIt2’s setup assistant.

Parameters:
  • urdf_path – Path to a Unified Robot Description Format file.

  • new_package_keyword – the string to replace package:// keyword

  • num_samples – number of samples to find the link that will always collide

  • verbose – print debug info

Returns:

Path to the generated SRDF file