simulation.utils.urdf package

Module package to create .urdf model definitions.

The package contains a number of classes that enable to define urdf robots through python.

For what? The urdf is very repetetive to write and requires prior knowledge on available tags and how they can be combined to a fully specified robot. Additionally, the commonly used xacro is less powerful than python and, again, another tool.

The basic idea used throughout the package is the inheritance from XmlObject. XmlObject.create_xml() creates a xml.etree.cElementTree.Element from the class instance. It does so by converting all instance attributes into xml attributes and sub elements. If a class attribute is an instance of a subclass of XmlObject, the objects XmlObject.create_xml() is called recursively.

The XmlObject in combination with dataclasses allows to create lightweight classes that define urdf components when converted to xml.

Submodules:

Summary

__all__ Classes:

Attribute

Basic class that will be converted into a xml attribute.

Axis

Axis(xyz: simulation.utils.urdf.core.Attribute = <factory>)

Box

Box(size: simulation.utils.urdf.core.Attribute)

CameraClip

CameraClip(near: float, far: float)

CameraDefinition

CameraDefinition(horizontal_fov: float, image: simulation.utils.urdf.camera.CameraImage, clip: simulation.utils.urdf.camera.CameraClip = None)

CameraImage

CameraImage(width: int, height: int, format: str)

CameraPlugin

CameraPlugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute, alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None)

CameraProperties

CameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None)

CameraSensor

CameraSensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute, plugin: simulation.utils.urdf.camera.CameraPlugin, update_rate: float, camera: simulation.utils.urdf.camera.CameraDefinition)

Child

Child(link: simulation.utils.urdf.core.Attribute)

Collision

Collision(origin: simulation.utils.urdf.core.Origin = None, geometry: simulation.utils.urdf.link.Geometry = None)

Color

Color(xyz: simulation.utils.urdf.core.Attribute = <factory>)

Cylinder

Cylinder(radius: simulation.utils.urdf.core.Attribute, length: simulation.utils.urdf.core.Attribute)

DepthCamera

DepthCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: simulation.utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.DepthCameraProperties, chassis_link: simulation.utils.urdf.link.Link)

DepthCameraPlugin

DepthCameraPlugin(name: simulation.utils.urdf.core.Attribute = ‘camera_plugin’, filename: simulation.utils.urdf.core.Attribute = ‘libgazebo_ros_openni_kinect.so’, alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None, depthImageTopicName: str = None, depthImageCameraInfoTopicName: str = None, pointCloudTopicName: str = None, pointCloudCutoff: float = None)

DepthCameraProperties

DepthCameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None, point_cloud_cutoff: float = None, point_cloud_topic_name: str = None)

Gazebo

Gazebo(inner: simulation.utils.urdf.core.XmlObject, reference: simulation.utils.urdf.core.Attribute = None)

Geometry

Geometry(value: simulation.utils.urdf.core.XmlObject)

Inertia

Inertia(ixx: simulation.utils.urdf.core.Attribute = 0, ixy: simulation.utils.urdf.core.Attribute = 0, ixz: simulation.utils.urdf.core.Attribute = 0, iyx: simulation.utils.urdf.core.Attribute = 0, iyy: simulation.utils.urdf.core.Attribute = 0, iyz: simulation.utils.urdf.core.Attribute = 0, izx: simulation.utils.urdf.core.Attribute = 0, izy: simulation.utils.urdf.core.Attribute = 0, izz: simulation.utils.urdf.core.Attribute = 0)

Inertial

Inertial(mass: float, inertia: simulation.utils.urdf.link.Inertia, origin: simulation.utils.urdf.core.Origin = None)

Joint

Joint(name: simulation.utils.urdf.core.Attribute, parent: simulation.utils.urdf.joint.Parent, child: simulation.utils.urdf.joint.Child, type: simulation.utils.urdf.core.Attribute = ‘fixed’, axis: simulation.utils.geometry.vector.Vector = None, limit: simulation.utils.urdf.joint.JointLimit = None, dynamics: simulation.utils.urdf.joint.JointDynamics = None, origin: simulation.utils.urdf.core.Origin = None)

JointDynamics

JointDynamics(damping: simulation.utils.urdf.core.Attribute = None, friction: simulation.utils.urdf.core.Attribute = None)

JointLimit

JointLimit(effort: simulation.utils.urdf.core.Attribute = None, lower: simulation.utils.urdf.core.Attribute = None, upper: simulation.utils.urdf.core.Attribute = None, velocity: simulation.utils.urdf.core.Attribute = None)

Link

Link(name: simulation.utils.urdf.core.Attribute, collision: simulation.utils.urdf.link.Collision = None, visual: simulation.utils.urdf.link.Collision = None, inertial: simulation.utils.urdf.link.Inertial = None)

Material

Material(name: simulation.utils.urdf.core.Attribute = None, color: simulation.utils.geometry.vector.Vector = None, texture: str = None)

Mesh

Mesh(filename: simulation.utils.urdf.core.Attribute, scale: simulation.utils.geometry.vector.Vector = None)

MonoCamera

MonoCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: simulation.utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.CameraProperties, chassis_link: simulation.utils.urdf.link.Link)

Origin

Origin(xyz: simulation.utils.urdf.core.Attribute = <factory>, rpy: simulation.utils.urdf.core.Attribute = <factory>)

Parent

Parent(link: simulation.utils.urdf.core.Attribute)

Plugin

Plugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute)

Sensor

Sensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute)

Sphere

Sphere(radius: simulation.utils.urdf.core.Attribute)

Visual

Visual(origin: Tuple = None, geometry: simulation.utils.urdf.link.Geometry = None, material: simulation.utils.urdf.link.Material = None)

XmlObject

Base class for all urdf xml objects.

class Attribute(val: str, name: Optional[str] = None)[source]

Basic class that will be converted into a xml attribute.

Important: Within a subclass of XmlObject an attribute can be defined by simply annotating a class variable with py:class:Attribute!

Example

>>> from dataclasses import dataclass
>>> from urdf.core import XmlObject, Attribute
>>> @dataclass
... class Example(XmlObject):
...     TAG = "example"
...     name: Attribute
...     value1: str
...     value2: float = None
>>> ex = Example("example_name",value1="I'm an example.")

The code block defines a simple example class that results in the xml string:

<example name="example_name">
  <value1>I'm an example.</value1>
</example>
Parameters
  • val – Attribute value.

  • nameOptionally the name of the can be provided. By default the name of the Attribute instance defines the name of the resulting xml attribute.

class XmlObject[source]

Base class for all urdf xml objects.

TAG = None
_get_val(val: Any) → str[source]

Convert a value to a string that is included into the xml.

create_xml(root_el: Optional[xml.etree.ElementTree.Element] = None) → xml.etree.ElementTree.Element[source]

Convert this instance into a xml element.

  • If the class of this instance does not define a tag, new xml elements from this instance are appended to the root_el. Otherwise, a sub element is created and returned.

  • Additionally to all instance attributes, a dictionary parameters can be used to define sub elements.

  • A Attribute type annotation for any of the object`s attributes, will result in a xml attribute.

Parameters

root_elOptional element that is used a parent xml element when provided.

save(file_path: str)[source]

Save this instance as a xml string to a file.

Parameters

file_path – Location to store the xml.

class Origin(xyz: simulation.utils.urdf.core.Attribute = <factory>, rpy: simulation.utils.urdf.core.Attribute = <factory>)[source]
TAG = 'origin'
xyz: simulation.utils.urdf.core.Attribute
rpy: simulation.utils.urdf.core.Attribute
classmethod from_vector(vector: simulation.utils.geometry.vector.Vector)[source]
classmethod from_list(lst: List[float])[source]
class Axis(xyz: simulation.utils.urdf.core.Attribute = <factory>)[source]
TAG = 'axis'
xyz: simulation.utils.urdf.core.Attribute
class Color(xyz: simulation.utils.urdf.core.Attribute = <factory>)[source]
TAG = 'color'
xyz: simulation.utils.urdf.core.Attribute
class Inertia(ixx: simulation.utils.urdf.core.Attribute = 0, ixy: simulation.utils.urdf.core.Attribute = 0, ixz: simulation.utils.urdf.core.Attribute = 0, iyx: simulation.utils.urdf.core.Attribute = 0, iyy: simulation.utils.urdf.core.Attribute = 0, iyz: simulation.utils.urdf.core.Attribute = 0, izx: simulation.utils.urdf.core.Attribute = 0, izy: simulation.utils.urdf.core.Attribute = 0, izz: simulation.utils.urdf.core.Attribute = 0)[source]
TAG = 'inertia'
ixx: simulation.utils.urdf.core.Attribute = 0
ixy: simulation.utils.urdf.core.Attribute = 0
ixz: simulation.utils.urdf.core.Attribute = 0
iyx: simulation.utils.urdf.core.Attribute = 0
iyy: simulation.utils.urdf.core.Attribute = 0
iyz: simulation.utils.urdf.core.Attribute = 0
izx: simulation.utils.urdf.core.Attribute = 0
izy: simulation.utils.urdf.core.Attribute = 0
izz: simulation.utils.urdf.core.Attribute = 0
class Inertial(mass: float, inertia: simulation.utils.urdf.link.Inertia, origin: simulation.utils.urdf.core.Origin = None)[source]
TAG = 'inertial'
mass: float
inertia: simulation.utils.urdf.link.Inertia
origin: simulation.utils.urdf.core.Origin = None
create_xml(root_el=None)[source]

Convert this instance into a xml element.

  • If the class of this instance does not define a tag, new xml elements from this instance are appended to the root_el. Otherwise, a sub element is created and returned.

  • Additionally to all instance attributes, a dictionary parameters can be used to define sub elements.

  • A Attribute type annotation for any of the object`s attributes, will result in a xml attribute.

Parameters

root_elOptional element that is used a parent xml element when provided.

class Box(size: simulation.utils.urdf.core.Attribute)[source]
TAG = 'box'
size: simulation.utils.urdf.core.Attribute
calculate_inertia(mass)simulation.utils.urdf.link.Inertia[source]
class Sphere(radius: simulation.utils.urdf.core.Attribute)[source]
TAG = 'sphere'
radius: simulation.utils.urdf.core.Attribute
calculate_inertia(mass)simulation.utils.urdf.link.Inertia[source]
class Cylinder(radius: simulation.utils.urdf.core.Attribute, length: simulation.utils.urdf.core.Attribute)[source]
TAG = 'cylinder'
radius: simulation.utils.urdf.core.Attribute
length: simulation.utils.urdf.core.Attribute
calculate_inertia(mass)simulation.utils.urdf.link.Inertia[source]
class Geometry(value: simulation.utils.urdf.core.XmlObject)[source]
TAG = 'geometry'
value: simulation.utils.urdf.core.XmlObject
class Mesh(filename: simulation.utils.urdf.core.Attribute, scale: simulation.utils.geometry.vector.Vector = None)[source]
TAG = 'mesh'
filename: simulation.utils.urdf.core.Attribute
scale: simulation.utils.geometry.vector.Vector = None
class Material(name: simulation.utils.urdf.core.Attribute = None, color: simulation.utils.geometry.vector.Vector = None, texture: str = None)[source]
TAG = 'material'
name: simulation.utils.urdf.core.Attribute = None
color: simulation.utils.geometry.vector.Vector = None
texture: str = None
class Visual(origin: Tuple = None, geometry: simulation.utils.urdf.link.Geometry = None, material: simulation.utils.urdf.link.Material = None)[source]
TAG = 'visual'
origin: Tuple = None
geometry: simulation.utils.urdf.link.Geometry = None
material: simulation.utils.urdf.link.Material = None
class Collision(origin: simulation.utils.urdf.core.Origin = None, geometry: simulation.utils.urdf.link.Geometry = None)[source]
TAG = 'collision'
origin: simulation.utils.urdf.core.Origin = None
geometry: simulation.utils.urdf.link.Geometry = None
TAG = 'link'
name: simulation.utils.urdf.core.Attribute
collision: simulation.utils.urdf.link.Collision = None
visual: simulation.utils.urdf.link.Collision = None
inertial: simulation.utils.urdf.link.Inertial = None
use_inertial_from_collision(mass: float)[source]
class JointDynamics(damping: simulation.utils.urdf.core.Attribute = None, friction: simulation.utils.urdf.core.Attribute = None)[source]
TAG = 'dynamics'
damping: simulation.utils.urdf.core.Attribute = None
friction: simulation.utils.urdf.core.Attribute = None
class JointLimit(effort: simulation.utils.urdf.core.Attribute = None, lower: simulation.utils.urdf.core.Attribute = None, upper: simulation.utils.urdf.core.Attribute = None, velocity: simulation.utils.urdf.core.Attribute = None)[source]
TAG = 'limit'
effort: simulation.utils.urdf.core.Attribute = None
lower: simulation.utils.urdf.core.Attribute = None
upper: simulation.utils.urdf.core.Attribute = None
velocity: simulation.utils.urdf.core.Attribute = None
class Parent(link: simulation.utils.urdf.core.Attribute)[source]
TAG = 'parent'
class Child(link: simulation.utils.urdf.core.Attribute)[source]
TAG = 'child'
class Joint(name: simulation.utils.urdf.core.Attribute, parent: simulation.utils.urdf.joint.Parent, child: simulation.utils.urdf.joint.Child, type: simulation.utils.urdf.core.Attribute = 'fixed', axis: simulation.utils.geometry.vector.Vector = None, limit: simulation.utils.urdf.joint.JointLimit = None, dynamics: simulation.utils.urdf.joint.JointDynamics = None, origin: simulation.utils.urdf.core.Origin = None)[source]
TAG = 'joint'
FIXED = 'fixed'
REVOLUTE = 'revolute'
CONTINUOUS = 'continuous'
name: simulation.utils.urdf.core.Attribute
parent: simulation.utils.urdf.joint.Parent
child: simulation.utils.urdf.joint.Child
type: simulation.utils.urdf.core.Attribute = 'fixed'
axis: simulation.utils.geometry.vector.Vector = None
limit: simulation.utils.urdf.joint.JointLimit = None
dynamics: simulation.utils.urdf.joint.JointDynamics = None
origin: simulation.utils.urdf.core.Origin = None
class Plugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute)[source]
TAG = 'plugin'
name: simulation.utils.urdf.core.Attribute
filename: simulation.utils.urdf.core.Attribute
class Gazebo(inner: simulation.utils.urdf.core.XmlObject, reference: simulation.utils.urdf.core.Attribute = None)[source]
TAG = 'gazebo'
inner: simulation.utils.urdf.core.XmlObject
reference: simulation.utils.urdf.core.Attribute = None
class Sensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute)[source]
TAG = 'sensor'
name: simulation.utils.urdf.core.Attribute
type: simulation.utils.urdf.core.Attribute
class MonoCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: simulation.utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.CameraProperties, chassis_link: simulation.utils.urdf.link.Link)[source]
sensor: simulation.utils.urdf.camera.CameraSensor
joint: simulation.utils.urdf.joint.Joint
plugin: simulation.utils.urdf.gazebo.Gazebo
class DepthCamera(name: str, origin: simulation.utils.urdf.core.Origin, size: simulation.utils.geometry.vector.Vector, mass: float, properties: simulation.utils.urdf.camera.DepthCameraProperties, chassis_link: simulation.utils.urdf.link.Link)[source]
joint: simulation.utils.urdf.joint.Joint
plugin: simulation.utils.urdf.gazebo.Gazebo
sensor: simulation.utils.urdf.camera.CameraSensor
class CameraClip(near: float, far: float)[source]
TAG = 'clip'
near: float
far: float
class CameraDefinition(horizontal_fov: float, image: simulation.utils.urdf.camera.CameraImage, clip: simulation.utils.urdf.camera.CameraClip = None)[source]
TAG = 'camera'
horizontal_fov: float
image: simulation.utils.urdf.camera.CameraImage
clip: simulation.utils.urdf.camera.CameraClip = None
class CameraImage(width: int, height: int, format: str)[source]
TAG = 'image'
width: int
height: int
format: str
class CameraPlugin(name: simulation.utils.urdf.core.Attribute, filename: simulation.utils.urdf.core.Attribute, alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None)[source]
alwaysOn: float = 1
updateRate: float = 0
frameName: str = None
cameraName: str = None
CxPrime: float = None
Cx: float = None
Cy: float = None
class DepthCameraPlugin(name: simulation.utils.urdf.core.Attribute = 'camera_plugin', filename: simulation.utils.urdf.core.Attribute = 'libgazebo_ros_openni_kinect.so', alwaysOn: float = 1, updateRate: float = 0, frameName: str = None, cameraName: str = None, CxPrime: float = None, Cx: float = None, Cy: float = None, depthImageTopicName: str = None, depthImageCameraInfoTopicName: str = None, pointCloudTopicName: str = None, pointCloudCutoff: float = None)[source]
name: simulation.utils.urdf.core.Attribute = 'camera_plugin'
filename: simulation.utils.urdf.core.Attribute = 'libgazebo_ros_openni_kinect.so'
depthImageTopicName: str = None
depthImageCameraInfoTopicName: str = None
pointCloudTopicName: str = None
pointCloudCutoff: float = None
class CameraSensor(name: simulation.utils.urdf.core.Attribute, type: simulation.utils.urdf.core.Attribute, plugin: simulation.utils.urdf.camera.CameraPlugin, update_rate: float, camera: simulation.utils.urdf.camera.CameraDefinition)[source]
name: simulation.utils.urdf.core.Attribute
type: simulation.utils.urdf.core.Attribute
plugin: simulation.utils.urdf.camera.CameraPlugin
update_rate: float
camera: simulation.utils.urdf.camera.CameraDefinition
class CameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None)[source]
horizontal_fov: float
update_rate: float
image_width: float
image_height: float
image_format: float
clip_near: float
clip_far: float
image_topic: str
info_topic: str
frame_name: str
optical_center_x: float = None
optical_center_y: float = None
class DepthCameraProperties(horizontal_fov: float, update_rate: float, image_width: float, image_height: float, image_format: float, clip_near: float, clip_far: float, image_topic: str, info_topic: str, frame_name: str, optical_center_x: float = None, optical_center_y: float = None, point_cloud_cutoff: float = None, point_cloud_topic_name: str = None)[source]
point_cloud_cutoff: float = None
point_cloud_topic_name: str = None