URDF Importer

Background Resources:

ResourceDescription
Python 3.8 Download pageDetailed information on installing and using Python 3.8
Robotic Operating System 2 - DocumentationDetailed information on ROS2
URDF SpecificationDetailed information on the URDF standard

Basic use

Running the importer

URDF files can be imported into a Vortex assembly file using the URDF import tool. The tool takes the form of a python script, compatible with python 3.8, and can be used from the command line, or as part of your own python scripts. For a step-by-step guide, see the URDF Import Tutorial.

From the command line:

 The script is located at: <Vortex_install_dir>\bin\vxurdf\urdf_to_vxassembly.py. The script can then be run via:

> <python38> <script location>\urdf_to_vxassembly.py --input_urdf <path_to_urdf_input> --output_vxassembly <path_to_vxassembly_output>

where <python38> is either your python 3.8 command (e.g., just python), or the location of the python 3.8 executable, <script location> is the location and name of the python script to be run, in this case, the URDF to VxAssembly import script, and after installing Vortex, is: <Vortex_install_dir>\bin\vxurdf. The location and name of the URDF file to be imported is denoted by: <path_to_urdf_input>, and the name and location of the output VxAssembly file is represented by <path_to_vxassembly_output>. The flags --input_urdf and --output_vxassembly can be shortened to -i and -o respectively. Note that:

  • The input path can be an absolute path, or a relative path which is given relative to the current command line directory. 
  • The directory for the output VxAssembly file must already exist, a new directory will not be created during import.
  • The help command --h or --help can be used after the script to obtain detailed descriptions of the arguments and their requirements

From a python script

Upon installation of Vortex, the location of the Vortex.py script was added to the PYTHONPATH, to allow the use of 'import Vortex' in your python scripts. The URDF import script is contained in a folder in the same place, and the URDF to VxAssembly import function can be accessed via:

Urdf import code snippet
# Import the urdf_to_vxassembly function from urdf_to_vxassembly.py
from vxurdf.urdf_to_vxassembly import urdf_to_vxassembly

# Call the function
urdf_to_vxassembly(urdf_filename='inputfile.urdf', vxassembly_filename='outputfile.vxassembly')

The same validation of file names and locations as is done using the command line, will also be performed after calling the function in a script, and, as before, both absolute and relative paths can be used.

Limitations

The URDF standard has a number of limitations and these are reflected in the importer. Once a URDF file is imported however, it is an assembly available to be manipulated in the same ways any Vortex assembly can be. The URDF standard is described in this URDF standard link and the limitations of what it can describe are explained in detail.

The current version of the URDF import script has a number of further limitations, listed here:

  • Currently, only the <robot>, <link> and <joint> tags are supported. Other tags which are part of the specification will notify the user that they are not supported during import, and will not affect the final VxAssembly created from the supplied URDF file. In particular, the importer does not utilize the information from <sensor>, <transmission> or <gazebo> tags. 
  • The following subtags of <joint> are not supported, and their corresponding information is not utilized, as they have no simple analogue within Vortex:
    • <calibration>
    • <mimic>
    • <safety_controller>
    • The <velocity> subtag of <limit> is also not supported.
  • The following subtags of <link> are not supported, and their corresponding information is not utilized.:
    • <visual> - as Vortex performs dynamic simulation involving contact, and visual geometries in URDF files are purely for visualization purposes, and contain no dynamic or contact information, they are not currently supported.
    • The <mesh> subtag of <geometry> - currently, the importer only supports collections of primitive (sphere, cylinder and box) collision geometries.
  • Vortex also requires a mass for each link. If no mass is provided, Vortex will initialize the object with the default mass of a part in Vortex (1kg mass, and a diagonal inertia matrix with entries of 0.4kgm2 )

Model Mapping

The following table contains a summary of the data from the URDF file which the importer uses, and how this data is used in Vortex. The URDF variables are arranged in their xml hierarchy to make tags and subtags easily visible. The Vortex equivalent variables can be found in the Vortex Editor inspector when the relevant constraint or part is selected. The exceptions to this are the constraint type and collision geometry type, which are selected before the object is added to the assembly. These mappings are documented in further detail in source code comments if more information is required.

Variable DescriptionURDF VariablesVortex equivalent
Name of the URDF filename



N/A

Version of the URDF file

version (if missing, defaults to 1.0)



N/A
Joint nameJoint













name


constraint name
Identity of the parent linkparent


Part 2
Identity of the child linkchild


Part 1 

Type of the joint

Types:

  • "unknown"
  • "revolute"
  • "continuous"
  • "prismatic"
  • "floating"
  • "planar"
  • "fixed"
type


Top level selection of type of constraint

Types:

  • N/A
  • Hinge
  • Hinge
  • Prismatic
  • No constraint used
  • A1P3 with the angular coordinate and primary axis locked
  • RPRO
Principal joint axisaxis


Primary axis of constraint

Position and orientation of the joint relative to the parent link's frame. 

origin


Part 1 reference part → Part 1

Part 2 reference part → Part 1

Offset→Position

Primary Axis

N.B. - Global transformations are used in Vortex, so the relative transformation information contained in the URDF joint is not directly used here. The information is included by setting the child link (Part 1) to be the reference part for the constraint.

Maximum joint effort (force/torque)limit



effort

Lock→Maximum Force
Maximum joint velocityvelocity

UNSUPPORTED
Joint limit (radians for revolute joints, meters for prismatic joints).lower

Limits→Lower Limit→Position 
Joint limit (radians for revolute joints, meters for prismatic joints).upper

Limits→Upper Limit→Position 
Static friction coefficient of the jointdynamics
 
friction

Friction coefficient

N.B. Friction scale assumed to be one. If the friction coefficient is set, the proportional friction flag is set to true, and the friction model is assumed to be Coulomb friction.

Joint dampingdamping

Friction->Loss
Link nameLink


















name


part name
Scalar massinertial


mass

Mass (defaults to 1kg if no URDF mass)
6 independent elements of the 3x3 inertia tensor (i.e. not necessarily defined in the principal axes)inertia

Inertia Tensor (defaults to a diagonal tensor with diagonal entries of 0.4 kgm2defined relative to the orientation of the part frame)

T his is the pose of the link's inertial reference frame, relative to the link reference frame. The origin of the inertial reference fram emust be at the center of gravity.

origin

Part→MassProperties→COM Offset (position)

N.B. orientation is encoded in inertia tensor. There is no separate inertial frame in Vortex

Collision objectscollision













Collision geometries

The reference frame of the collision element, relative to the reference frame of the link.

origin

Local transform
Box-shaped geometrygeometry








box
Collision Geometry Type: Box 
Dimension in x-y-z
sizeBox → Dimensions
Cylinder-shaped geometrycylinder
Collision Geometry Type: Cylinder
Radius of cylinder
radiusCylinder → Radius
Height of cylinder
lengthCylinder → Height
Sphere-shaped geometrysphere
Collision Geometry Type: Sphere
Radius of sphere
radiusSphere → Radius

Troubleshooting

There are a number of warning and error messages designed to help you discover problems with your URDF import process if the process fails for some reason. Warning messages are simply warnings, the import will proceed regardless, but the warnings inform you if data may be lost, or remain unused for some reason. Exceptions stop the import process, these will usually only appear if the URDF input file has an error in it. 

Example warning messages

WarningDescription
'Tag: --, unsupported in Vortex Assembly import
A tag in your URDF file is a supported tag in the URDF standard, but the information will not be used by Vortex
'Attribute: --, unsupported in Vortex Assembly import
An attribute in your URDF file is a supported attribute in the URDF standard, but the information will not be used by Vortex

Example exceptions

ExceptionDescription
"Invalid -- tag: --"
The URDF contains a tag other than those supported by the basic standard. Perhaps a tag name has been misspelled.
"Invalid -- type: --"
The URDF contains a type other than the a valid one, e.g. a joint with an invalid type, or a geometry which is not a box, cylinder or sphere. Perhaps the type has been misspelled.
"Required -- not set in XML: --"
A URDF tag is missing a required field, e.g. every link must have a name. Check the specified tag in your URDF to see if a required field is missing, or an attribute tag is misspelled.
"The version attribute should be in the form 'x.y'"
"Empty major or minor number is not allowed"
"Version number must be positive"

The version number of the URDF is incorrectly formatted. The version number is positive, and consists of two numbers separated by a period, e.g. 1.2 or 2.4

If the version number is missing, a default of 1.0 will be assumed.

"Multiple roots detected, invalid URDF."
"No roots detected, invalid URDF."
The topology of the robot represented by the URDF is not a tree shape, e.g. a child link has multiple parents, or there robot has loops.