ManipulaPy.urdf β€” URDF Subpackage (v1.3.2+)#

Added in version 1.3.2: New native NumPy 2.0-compatible URDF parser introduced as the recommended alternative to the legacy urdf_processor module.

Module overview#

ManipulaPy.urdf is a self-contained, NumPy 2.0-compatible URDF parser written specifically for ManipulaPy. It has zero hard dependencies on third-party URDF libraries (trimesh and pybullet are loaded lazily and only when meshes or alternative backends are needed). The parser understands package:// URIs, file:// URIs, ROS 1 / ROS 2 package discovery, and Xacro macro expansion. Loading a URDF returns a URDF object that can be converted directly into a SerialManipulator or a ManipulatorDynamics instance.

URDF class#

class ManipulaPy.urdf.URDF(name='robot', links=None, joints=None, materials=None, transmissions=None, filename_handler=None)[source]#

Bases: object

ManipulaPy native URDF parser.

Optimized for robotics kinematics and dynamics workflows with direct integration to SerialManipulator and ManipulatorDynamics.

Example

>>> robot = URDF.load("robot.urdf")
>>> robot.num_actuated_joints
6
>>> fk = robot.link_fk()
>>> manipulator = robot.to_serial_manipulator()
Parameters:
  • name (str)

  • links (List[Link] | None)

  • joints (List[Joint] | None)

  • materials (Dict[str, Material] | None)

  • transmissions (List[Transmission] | None)

  • filename_handler (Callable[[str], str] | None)

classmethod load(filename, load_meshes=False, mesh_dir=None, backend='builtin')[source]#

Load URDF from file.

Parameters:
  • filename (str | Path) – Path to URDF or XACRO file

  • load_meshes (bool) – Load mesh geometry data

  • mesh_dir (str | Path | None) – Base directory for mesh file resolution

  • backend (str) – Parser backend - β€œbuiltin” (default) or β€œpybullet”

Returns:

URDF object

Return type:

URDF

Note

  • β€œbuiltin”: Native ManipulaPy parser (NumPy 2.0 compatible)

  • β€œpybullet”: PyBullet-based parser (requires pybullet package)

classmethod from_xml_string(xml_string, **kwargs)[source]#

Load URDF from XML string.

Parameters:
Return type:

URDF

All links in order.

property joints: List[Joint]#

All joints in order.

property transmissions: List[Transmission]#

All transmissions.

property transmission_map: Dict[str, Transmission]#

Transmission name to Transmission mapping.

Link name to Link mapping.

property joint_map: Dict[str, Joint]#

Joint name to Joint mapping.

property actuated_joints: List[Joint]#

Non-fixed, non-mimic joints in kinematic chain order.

property actuated_joint_names: List[str]#

Names of actuated joints.

property num_actuated_joints: int#

Number of actuated (non-fixed, non-mimic) joints.

property num_dofs: int#

Alias for num_actuated_joints.

Root link of the kinematic tree.

All root links (supports multi-root URDFs).

End effector (leaf) links.

Primary end effector link (first end link).

property kinematic_chain: List[Joint]#

Ordered list of joints from root to leaves.

property joint_limits: List[Tuple[float, float]]#

Joint limits as list of (lower, upper) tuples.

property cfg: ndarray#

Current configuration as array.

update_cfg(cfg)[source]#

Update joint configuration.

Parameters:

cfg (ndarray | List[float] | Dict[str, float] | None) – Configuration as dict {joint_name: value}, array, or list

Return type:

None

Compute forward kinematics for links.

Parameters:
  • cfg (ndarray | List[float] | Dict[str, float] | None) – Joint configuration (uses current if None)

  • links (List[str] | None) – Specific link names to compute (None = all)

  • use_names (bool) – Return dict with string keys instead of Link keys

Returns:

Dict mapping links (or link names) to 4x4 transformation matrices

Return type:

Dict[Link, ndarray] | Dict[str, ndarray]

Batch compute forward kinematics for multiple configurations.

Optimized vectorized implementation.

Parameters:
  • cfgs (ndarray) – Array of configurations (N, num_dofs)

  • links (List[str] | None) – Specific link names to compute (None = all)

Returns:

Dict mapping link names to (N, 4, 4) transformation arrays

Return type:

Dict[str, ndarray]

get_transform(frame_to, frame_from='world', cfg=None)[source]#

Get transform between two frames.

Parameters:
  • frame_to (str) – Target frame (link name)

  • frame_from (str) – Source frame (link name or β€œworld”)

  • cfg (ndarray | Dict[str, float] | None) – Joint configuration

Returns:

4x4 transformation matrix from frame_from to frame_to

Return type:

ndarray

extract_screw_axes(tip_link=None)[source]#

Extract screw axis parameters for ManipulaPy.

Parameters:

tip_link (str | None) – Optional link name to use as end-effector. Defaults to first end link.

Returns:

M, S_list, B_list, G_list, omega_list, r_list, joint_limits

Return type:

Dict with keys

to_serial_manipulator(tip_link=None)[source]#

Convert to ManipulaPy SerialManipulator.

Parameters:

tip_link (str | None) – Optional link name to use as end-effector. Defaults to first end link.

Returns:

SerialManipulator instance ready for IK/FK

Return type:

SerialManipulator

to_manipulator_dynamics()[source]#

Convert to ManipulaPy ManipulatorDynamics.

Returns:

ManipulatorDynamics instance ready for dynamics computation

Return type:

ManipulatorDynamics

show(cfg=None, use_collision=False)[source]#

Visualize the robot.

Parameters:
  • cfg (ndarray | Dict[str, float] | None) – Joint configuration

  • use_collision (bool) – Show collision geometry instead of visual

Return type:

None

animate(cfg_trajectory, loop_time=3.0, use_collision=False)[source]#

Animate robot along trajectory.

Parameters:
  • cfg_trajectory (Dict[str, ndarray] | ndarray) – Joint trajectories {joint_name: array} or (N, DOF) array

  • loop_time (float) – Animation duration in seconds

  • use_collision (bool) – Use collision geometry

Return type:

None

Get link by name.

Parameters:

name (str)

Return type:

Link | None

get_joint(name)[source]#

Get joint by name.

Parameters:

name (str)

Return type:

Joint | None

get_chain(root, tip)[source]#

Get joint chain between two links.

Parameters:
  • root (str) – Root link name

  • tip (str) – Tip link name

Returns:

List of joints from root to tip

Return type:

List[Joint]

copy()[source]#

Create a deep copy of the URDF.

Return type:

URDF

__repr__()[source]#

Return a compact debug representation.

Return type:

str

__str__()[source]#

Return a human-readable URDF summary.

Return type:

str

Use URDF.load() to parse a URDF (or Xacro) file from disk. The backend argument selects the parser implementation:

  • "builtin" (default) β€” the native ManipulaPy parser. NumPy 2.0 compatible, no extra installs required.

  • "pybullet" β€” PyBullet-based loader. Requires the [simulation] extra (pip install ManipulaPy[simulation]).

Once loaded, call URDF.to_serial_manipulator() to obtain a kinematics-ready SerialManipulator, or URDF.to_manipulator_dynamics() to obtain a fully populated ManipulatorDynamics (mass, inertia, screw axes, joint limits):

from ManipulaPy.urdf import URDF
from ManipulaPy.ManipulaPy_data import get_robot_urdf

robot = URDF.load(get_robot_urdf("ur5"), backend="builtin")
serial = robot.to_serial_manipulator()
dynamics = robot.to_manipulator_dynamics()

PackageResolver class#

class ManipulaPy.urdf.PackageResolver(base_path=None, package_map=None, search_paths=None, use_ros=True)[source]#

Resolve package:// URIs and relative paths for URDF resources.

Supports multiple resolution strategies: 1. Explicit package map (package_name -> path) 2. ROS package paths (via rospack or ament_index) 3. Environment-based search paths 4. Base path relative resolution

Example

>>> resolver = PackageResolver()
>>> resolver.add_package("ur_description", "/opt/ros/melodic/share/ur_description")
>>> resolved = resolver.resolve("package://ur_description/meshes/ur5/visual/base.dae")
"/opt/ros/melodic/share/ur_description/meshes/ur5/visual/base.dae"
Parameters:
add_package(name, path)[source]#

Add a package to the resolver.

Parameters:
  • name (str) – Package name

  • path (str | Path) – Path to package root directory

Return type:

None

add_search_path(path)[source]#

Add a search path for package discovery.

Parameters:

path (str | Path) – Directory to search for packages

Return type:

None

resolve(uri)[source]#

Resolve a URI to an absolute file path.

Handles: - package://package_name/path/to/file - file:///absolute/path - Relative paths - Absolute paths

Parameters:

uri (str) – URI or path to resolve

Returns:

Resolved absolute path (or original if unresolvable)

Return type:

str

create_handler()[source]#

Create a filename handler function for the parser.

Returns:

Function that resolves URIs to paths

Return type:

Callable[[str], str]

list_packages()[source]#

List all known packages.

Returns:

Dictionary of package names to paths

Return type:

Dict[str, Path]

list_search_paths()[source]#

List all search paths.

Returns:

List of search paths

Return type:

List[Path]

classmethod for_urdf(urdf_path)[source]#

Create a resolver configured for a specific URDF file.

Automatically sets base_path to the URDF’s directory and adds common relative package locations.

Parameters:

urdf_path (str | Path) – Path to the URDF file

Returns:

Configured PackageResolver

Return type:

PackageResolver

Mesh path resolution#

When a URDF references meshes via package://<name>/<path>, PackageResolver walks the following strategies, in order, to map the URI to a real file on disk:

  1. Explicit PackageResolver.add_package() mapping β€” highest precedence. Once a package is pinned with add_package(name, path), the resolver never falls through to the other strategies for that package: if the requested file does not exist under the pinned root, the original URI is returned with a warning. This is the documented escape hatch for ambiguous workspaces.

  2. Search paths β€” every entry in search_paths is tried in both package-rooted (<search_path>/<package_name>/<rel>) and flat (<search_path>/<rel>) form.

  3. ROS package discovery β€” only when use_ros=True (the default). Uses ament_index_python (ROS 2), then rospkg / catkin_find (ROS 1), then any directories listed in ROS_PACKAGE_PATH and AMENT_PREFIX_PATH.

  4. base_path fallback β€” <base_path>/<rel>, useful when the URDF lives next to its meshes.

  5. Ancestor heuristic β€” checks up to three parent directory levels above base_path for either <ancestor>/<package>/<rel> or <ancestor>/<rel>. This catches the common package/urdf/robot.urdf and package/robots/model.urdf layouts.

Candidates from strategies 2-5 are deduplicated by their canonical (symlink-resolved) path before the ambiguity check, so symlinked or case-insensitive workspaces do not cause spurious β€œmultiple matches” warnings. If two genuinely distinct files match a single package:// URI, the resolver refuses to guess and emits a warning recommending an explicit add_package() call to disambiguate.

Two security-conscious behaviours are worth noting:

  • .. traversal segments inside package://name/... paths are rejected with a warning β€” the resolver returns the original URI rather than escaping the package root.

  • file:// URIs are parsed via urllib.parse.urlparse() and urllib.request.url2pathname(), so Windows-style file:///C:/... URIs resolve correctly.

Examples#

from ManipulaPy.urdf import URDF, PackageResolver
from ManipulaPy.ManipulaPy_data import get_robot_urdf

# Default load with native parser (NumPy 2.0 compatible)
robot = URDF.load(get_robot_urdf("ur5"))
serial = robot.to_serial_manipulator()
dynamics = robot.to_manipulator_dynamics()

# Custom resolver for unbundled meshes β€” pass package_map through
# the parser for the same effect as resolver.add_package(...).
from ManipulaPy.urdf.parser import URDFParser
robot = URDFParser.parse_file(
    "custom.urdf",
    package_map={"ur_description": "/opt/ros/jazzy/share/ur_description"},
    load_meshes=True,
)

# Or build a resolver directly for advanced use:
resolver = PackageResolver()
resolver.add_package("ur_description", "/opt/ros/jazzy/share/ur_description")
resolved = resolver.resolve("package://ur_description/meshes/ur5/visual/base.dae")

# Use PyBullet's loader when simulation interoperability is needed
robot = URDF.load("custom.urdf", backend="pybullet")

See also#

  • URDF Processor API Reference β€” legacy URDFToSerialManipulator API (still supported, but the native parser is recommended for new code).