Urdfpy Documentation

Urdfpy is a simple pure-Python library for loading, manipulating, and exporting URDF files and robot specifications. For example, here’s a rendering of a UR5 robot moving around after being loaded by this library.

_images/ur5.gif

Installation and Setup Guide

Python Installation

This package is pip-installable for any Python version. Simply run the following command:

pip install urdfpy

Installing in Development Mode

If you’re planning on contributing to this repository, please see the Development Guide.

Usage Examples

This page documents several simple use cases for you to try out. For full details, see the API Reference, and check out the full class reference for URDF.

Loading from a File

You can load a URDF from any .urdf file, as long as you fix the links to be relative or absolute links rather than ROS resource URLs.

>>> from urdfpy import URDF
>>> robot = URDF.load('tests/data/ur5/ur5.urdf')

Saving to a File

You can also export the URDF to a file. Any meshes and images will be dumped using their original relative or absolute names. If the names are relative, they’ll be dumped relative to the new URDF file.

>>> robot.save('/tmp/ur5/ur5.urdf')

Doing Forward Kinematics

You have a variety of options for performing forward kinematics. For example, you can get the kinematics of the robot’s links:

>>> fk = robot.link_fk()
>>> print(fk[robot.links[0]])
array([[1., 0., 0., 0.],
       [0., 1., 0., 0.],
       [0., 0., 1., 0.],
       [0., 0., 0., 1.]])
>>> print(fk[robot.links[1]])
array([[1.   , 0.   , 0.   , 0.   ],
       [0.   , 1.   , 0.   , 0.   ],
       [0.   , 0.   , 1.   , 0.089],
       [0.   , 0.   , 0.   , 1.   ]])
>>> fk = robot.link_fk(cfg={'shoulder_pan_joint' : 1.0})
>>> print(fk[robot.links[1]])
array([[ 0.54 , -0.841,  0.   ,  0.   ],
       [ 0.841,  0.54 ,  0.   ,  0.   ],
       [ 0.   ,  0.   ,  1.   ,  0.089],
       [ 0.   ,  0.   ,  0.   ,  1.   ]])

The fk result is a map from Link objects to their poses relative to the robot’s base link as 4x4 homogenous transform matrices. You can pass a joint configuration, which is a map from joints (or joint names) to joint configuration values.

You can also directly get the poses of the robot’s Trimesh geometries:

>>> fk = robot.visual_trimesh_fk()
>>> print(type(list(fk.keys())[0]))
trimesh.base.Trimesh
>>> fk = robot.collision_trimesh_fk()
>>> print(type(list(fk.keys())[0]))
trimesh.base.Trimesh

Visualization

Urdfpy also comes bundled with two simple visualization functions.

You can visualize a robot in a static configuration:

>>> robot.show(cfg={
...     'shoulder_lift_joint': -2.0,
...     'elbow_joint': 2.0
... })
...
_images/ur5_static.png

Or animate it over a configuration trajectory:

>>> robot.animate(cfg_trajectory={
...     'shoulder_pan_joint' : [-np.pi / 4, np.pi / 4],
...     'shoulder_lift_joint' : [0.0, -np.pi / 2.0],
...     'elbow_joint' : [0.0, np.pi / 2.0]
... })
...
_images/ur5_three_joints.gif

API Reference

Functions

rpy_to_matrix(coords) Convert roll-pitch-yaw coordinates to a 3x3 homogenous rotation matrix.
matrix_to_rpy(R[, solution]) Convert a 3x3 transform matrix to roll-pitch-yaw coordinates.
xyz_rpy_to_matrix(xyz_rpy) Convert xyz_rpy coordinates to a 4x4 homogenous matrix.
matrix_to_xyz_rpy(matrix) Convert a 4x4 homogenous matrix to xyzrpy coordinates.

Classes

URDFType() Abstract base class for all URDF types.
Box(size) A rectangular prism whose center is at the local origin.
Cylinder(radius, length) A cylinder whose center is at the local origin.
Sphere(radius) A sphere whose center is at the local origin.
Mesh(filename[, scale, meshes]) A triangular mesh object.
Geometry([box, cylinder, sphere, mesh]) A wrapper for all geometry types.
Texture(filename[, image]) An image-based texture.
Material(name[, color, texture]) A material for some geometry.
Collision(name, origin, geometry) Collision properties of a link.
Visual(geometry[, name, origin, material]) Visual properties of a link.
Inertial(mass, inertia[, origin]) The inertial properties of a link.
JointCalibration([rising, falling]) The reference positions of the joint.
JointDynamics(damping, friction) The dynamic properties of the joint.
JointLimit(effort, velocity[, lower, upper]) The limits of the joint.
JointMimic(joint[, multiplier, offset]) A mimicry tag for a joint, which forces its configuration to mimic another joint’s.
SafetyController(k_velocity[, k_position, …]) A controller for joint movement safety.
Actuator(name[, mechanicalReduction, …]) An actuator.
TransmissionJoint(name, hardwareInterfaces) A transmission joint specification.
Transmission(name, trans_type[, joints, …]) An element that describes the relationship between an actuator and a joint.
Joint(name, joint_type, parent, child[, …]) A connection between two links.
Link(name, inertial, visuals, collisions) A link of a rigid object.
URDF(name, links[, joints, transmissions, …]) The top-level URDF specification.

Development Guide

Read this guide before doing development in urdfpy.

Setting Up

To set up the tools you’ll need for developing, you’ll need to install urdfpy in development mode. Start by installing the development dependencies:

git clone https://github.com/mmatl/urdfpy.git
cd urdfpy
pip install -e .[dev,docs]

Next, install the git pre-commit hooks with the following command:

pre-commit install

This step is crucial. It will install a pre-commit git hook that runs the flake8 style checker on your code before allowing you to commit. The style checker isn’t just an annoyance – it does a lot more than just check for trailing whitespace! It can identify missing or undefined variable names, unused imports, and a whole host of other potential problems in your code.

Running Code Style Checks

To run the style checker on all files under version control, simply run the following command:

pre-commit run --all-files

If you’d like to run the style checker more selectively, you can run the flake8 command directly on a directory (recursively) or on an individual file:

flake8 --ignore=E231,W504 /path/to/files

For more information, please see the flake8 documentation.

Running Tests

This project uses pytest, the standard Python testing framework. Their website has tons of useful details, but here are the basics.

To run the testing suite, simply navigate to the top-level folder in urdfpy and run the following command:

pytest -v tests

You should see the testing suite run. There are a few useful command line options that are good to know:

  • -s - Shows the output of stdout. By default, this output is masked.
  • --pdb - Instead of crashing, opens a debugger at the first fault.
  • --lf - Instead of running all tests, just run the ones that failed last.
  • --trace - Open a debugger at the start of each test.

You can see all of the other command-line options here.

By default, pytest will look in the tests folder recursively. It will run any function that starts with test_ in any file that starts with test_. You can run pytest on a directory or on a particular file by specifying the file path:

pytest -v tests/unit/utils/test_transforms.py

You can also test a single function in a file:

pytest -v tests/unit/utils/test_images.py::test_rgbd_image

Generating Code Coverage Reports

To generate code coverage documentation, re-run the tests with the --cov option set:

pytest --cov=urdfpy tests

This will dump a code coverage file. To view it in a nice HTML document, run the following command:

coverage html

The generated HTML homepage will be stored at htmlcov/index.html.

Building Documentation

To build urdfpy’s documentation, go to the docs directory and run make with the appropriate target. For example,

cd docs/
make html

will generate HTML-based docs, which are probably the easiest to read. The resulting index page is at docs/build/html/index.html. If the docs get stale, just run make clean to remove all build files.

Indices and tables