Skip to content

Tools

Utility functions for working with robot models.

Proto to URDF Converter

convert_proto_to_urdf

convert_proto_to_urdf(
    proto_path="pibsim_webots/protos/pib.proto",
    urdf_path="pib_model.urdf",
)

Convert a Webots .proto file to URDF format.

This is a preprocessing tool for regenerating the URDF from the original Webots robot definition file.

Parameters:

Name Type Description Default
proto_path str

Path to the Webots .proto file.

'pibsim_webots/protos/pib.proto'
urdf_path str

Path to write the output URDF file.

'pib_model.urdf'

Returns:

Type Description
str

The generated URDF as a string.

Raises:

Type Description
FileNotFoundError

If proto_path doesn't exist.

Example

from pib3.tools import convert_proto_to_urdf urdf = convert_proto_to_urdf( ... "pibsim_webots/protos/pib.proto", ... "pib_model.urdf" ... )

Source code in pib3/tools/proto_converter.py
def convert_proto_to_urdf(
    proto_path: str = "pibsim_webots/protos/pib.proto",
    urdf_path: str = "pib_model.urdf",
) -> str:
    """
    Convert a Webots .proto file to URDF format.

    This is a preprocessing tool for regenerating the URDF from the
    original Webots robot definition file.

    Args:
        proto_path: Path to the Webots .proto file.
        urdf_path: Path to write the output URDF file.

    Returns:
        The generated URDF as a string.

    Raises:
        FileNotFoundError: If proto_path doesn't exist.

    Example:
        >>> from pib3.tools import convert_proto_to_urdf
        >>> urdf = convert_proto_to_urdf(
        ...     "pibsim_webots/protos/pib.proto",
        ...     "pib_model.urdf"
        ... )
    """
    if not os.path.exists(proto_path):
        raise FileNotFoundError(f"Proto file not found: {proto_path}")

    print(f"Reading proto file: {proto_path}")
    with open(proto_path) as f:
        text = f.read()

    print("Parsing proto file...")
    robot_node = parse_proto(tokenize(text))

    print("Generating URDF...")
    urdf_str = generate_urdf(robot_node)

    with open(urdf_path, "w") as f:
        f.write(urdf_str)

    print(f"URDF generated: {urdf_path}")

    joint_count = urdf_str.count('<joint name=')
    link_count = urdf_str.count('<link name=')
    print(f"Generated {link_count} links and {joint_count} joints")

    return urdf_str

Purpose

The PIB robot is originally defined in Webots' .proto format. This tool converts it to URDF (Unified Robot Description Format) for use with roboticstoolbox-python.

Pre-generated URDF

The package includes a pre-generated URDF file. You only need this tool if you modify the Webots proto file.

Usage

from pib3.tools import convert_proto_to_urdf

# Convert proto to URDF
urdf_string = convert_proto_to_urdf(
    proto_path="pibsim_webots/protos/pib.proto",
    urdf_path="pib_model.urdf",
)

print(f"Generated URDF with {urdf_string.count('<link')} links")

Command Line

python -m pib3.tools.proto_converter

This generates pib_model.urdf from the default proto location.

Conversion Details

The converter handles:

Webots Concept URDF Equivalent
Solid <link>
HingeJoint <joint type="revolute">
Transform Visual/collision <origin>
Shape with Mesh <visual> and <collision>
Physics <inertial>
Motor limits <limit>

Coordinate System

The canonical format uses Webots motor radians directly. The URDF generated by this converter uses the same coordinate system as Webots motors.

Example Output

<?xml version="1.0"?>
<robot name="pib">
  <link name="base_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry><mesh filename="urdf_body.stl"/></geometry>
    </visual>
  </link>

  <joint name="shoulder_vertical_left" type="revolute">
    <parent link="base_link"/>
    <child link="urdf_shoulder_vertical_1"/>
    <origin xyz="0.085 0.055 0.362" rpy="..."/>
    <axis xyz="0 1 0"/>
    <limit lower="0" upper="3.14" effort="10" velocity="20"/>
  </joint>

  <!-- ... more links and joints ... -->
</robot>

Calibration Tool

For calibrating joint limits on the real robot, see the Calibration Guide.

Internal Utilities

Vector Math Functions

The proto converter includes internal vector/matrix utilities:

# Not part of public API, but documented for reference:

normalize(v)           # Normalize 3D vector
axis_angle_to_matrix() # Convert axis-angle to rotation matrix
matrix_to_rpy()        # Convert matrix to roll-pitch-yaw

These are used internally for coordinate transformations during URDF generation.