Essentially what it says in the title. I always wanted python-native data bindings for SDFormat XML, and over the last two weeks, I’ve decided to finally made it happen. As a side-effect of this effort, I also created (versioned) XSD1.1 bindings for all SDFormat versions (SDFormat can not be efficiently described by XSD1.0) Both, the bindings and the schemata are part of ropy, and I have an open PR upstream with the schema generation script that - at the time of this writing - awaits feedback from the ignition team.
I am aware that python has xml.etree
and lxml.etree
, which can parse SDF (since it is XML); however, the bindings come with IntelliSense/auto-complete, validation (statically via mypy or at runtime via pydantic/marshmallow), and automatic population of default values.
Another advantage of being class-bassed is automatic type-conversion. Once another upstream dependency releases its new version in the next couple of days you can replace the parsing logic of specific SDF elements (classes) with your desired parsing logic. With this, you can, for example, directly turn any vector (mainly thinking about poses) into tuples, or numpy-arrays. You could split them into a pose.rotation
(which you can further convert into a quaternion) and pose.translation
or turn them into PyTorch/TensorFlow tensors. You write parsing functions for the elements of your choice, inject it into the parser and it (should) handle the rest … alternatively, you just roll with the default and get the type that SDF promises to give you.
Here is a code example (without type conversion)
from ropy.ignition.sdformat.bindings.v18 import sdf
import ropy.ignition as ign
from ropy.ignition.sdformat.bindings import v18
from pathlib import Path
# declarative style
# nesting objects inside the constructor
ground_plane = v18.model.Model(
static=True,
name="ground_plane",
link=[
v18.Link(
collision=v18.Collision(
v18.Geometry(plane=v18.Geometry.Plane(normal="1 0 0", size="1.4 6.3"))
),
visual=v18.Visual(
v18.Geometry(plane=v18.Geometry.Plane(normal="0 1 0", size="2 4"))
),
)
],
)
# procedual style
# also available as v18.ModelModel (due to name collision within SDF spec)
box = v18.model.Model()
box.pose = v18.model.Model.Pose("0 0 2.5 0 0 0", relative_to="ground_plane")
box.link.append(v18.Link())
box.link[0].name = "link"
# set-up collision
box.link[0].collision.append(v18.Collision())
box.link[0].collision[0].name = "collision"
box.link[0].collision[0].geometry = v18.Geometry.Box("1 2 3")
box.link[0].collision[0].surface = v18.Collision.Surface()
box.link[0].collision[0].surface.contact = v18.Collision.Surface.Contact(
collide_bitmask=171
)
# set-up visual
box.link[0].visual.append(v18.Visual())
box.link[0].visual[0].name = "box_vis"
box.link[0].visual[0].geometry = v18.Geometry.Box("1 2 3")
root = v18.Sdf(world=[v18.World(name="shapes_world", model=[ground_plane, box])])
# elements are populated with default values where applicable
print(f"Gravity set to: {root.world[0].gravity}")
# Gravity set to: 0 0 -9.8
# and of course you can serialize to SDF
sdf_string = ign.sdformat.dumps(root, format=True)
# and write the string into a file
Path("my_world.sdf").write_text(sdf_string)
# or (more old-school) via open(...)
with open("my_world.sdf", "w") as sdf_file:
print(sdf_string, file=sdf_file)
# loading is similary straight forward
sdf_string = Path("my_world.sdf").read_text()
root = ign.sdformat.loads(sdf_string)
# or again via open(...)
with open("my_world.sdf", "r") as sdf_file:
sdf_string = sdf_file.read()
root = ign.sdformat.loads(sdf_string)
# Note that ropy will by default auto-detect the SDF version from sdf's version
# attribute (all versions are supported). Alternatively, you can manually
# overwrite the auto-detect with a specific version.
sdf_reloaded = ign.sdformat.reads(sdf_string, version="1.6")
# you can assign the same object in multiple places to link the properties
box_geometry = v18.Geometry()
box_geometry.box = v18.Geometry.Box("1 2 3")
box.link[0].collision[0].geometry = box_geometry
box.link[0].visual[0].geometry = box_geometry
# and change both properties at the same time
box_geometry.box.size = "2 5 2"
print(ign.sdformat.dumps(root, format=True))
# however this linking will (of course) not survive serialization.
I’ll also lobby briefly for ropy’s other big feature: ropy.transform. ropy.transform
is a numpy-based version of ROS TF2. The main difference is that it works with arbitrary directed graphs (can be circular, not restricted to trees only), works in N dimensions, and is fully vectorized/tensorized.
You can do 6-dimensional rotations, sure, but at the moment I mainly use it to neatly transform end-effector/gripper positions into camera coordinates (pixels) with a line like cam_pos = gripper_frame.transform(x, "camera_1")
. Projections, too, work between arbitrary dimensions, so it should be possible to create some nice joint-space visualizations if anybody has a cool idea.
Being fully vectorized means that you can toss in batches (of points or joint configurations) and you will get full SIMD support (SSE/AVX/…). The same will happen if both points and configurations are batches, and you obviously get the familiar numpy broadcasting support. You can use a multi-threadded BLAS/LAPACK backend for further acceleration, or - it’s numpy based - toss it into dask to scale it to clusters, or use @tf.numpy_function
on it to make it part of your ML model (not GPU accelerated). Python is pretty flexible here. Oh and it is also possible, if you lobby for it, to create a torch/tf backend for ropy.transform
, which will allow GPU acceleration and backdrop through the graph. (sorry for the TL:DR; I’m quite nerdy when it comes to HPC.)
The reason I’m mentioning all this is that my next step (after adding <include>
resolution with fuel support) is to write a function that can convert the parsed SDFormat into a ropy.transform
graph. Which (without too much effort) could mean that you can fetch your ignition simulation as SDF and dump it onto the GPU for some computation (probably RL/ML). Alternatively, you can fetch the simulation state and efficiently do forward kinematics for a couple thousand potential joint configurations in your new IK/planning algorithm. Is this useful? I have no idea … but it sounds pretty cool, so I thought it’s fun to point out.
Note: The original version had many more links to all the related projects. However, I am apparently not allowed to add more than two per post … so they are all gone now
Related Links:
- Binding Docs: ropy.ignition — ropy documentation
- XSD Schemata: ropy/ropy/ignition/sdformat/schema at main · FirefoxMetzger/ropy · GitHub