dair_pll.urdf_utils
Utility functions for generating URDF’s for a given multibody system.
The URDFFindOrDefault
class searches for elements in an urdf’s xml tree,
and places a default in the event that the element does not exist. Many
string literals are instantiated here for convenience.
The UrdfGeometryRepresentationFactory
generates URDF XML representations
of a CollisionGeometry
, and fill_link_with_parameterization
dumps
these representations into a URDF “link” tag.
- class dair_pll.urdf_utils.UrdfFindOrDefault[source]
Bases:
object
URDF XML tool to automatically fill in default element tree structures.
URDF’s often represent an identifiable unit (e.g. a body’s spatial inertia) as a subtree of XML elements.
URDFFindOrDefault
implements a generalization of thexml.etree.ElementTree.find()
method, which fills in a default subtree according to the tree structure given in_URDF_DEFAULT_TREE
, with each element given tags according to_URDF_DEFAULT_ATTRIBUTES
.Typical usage example:
# element is an empty <inertial></inertial> # obtain default mass mass_element = URDFFindOrDefault.find(element, "mass") # element is now <inertial><mass value="0." /></inertial> # mass_element is now the child of element, <mass value="0." />
- static find(element, sub_element_type)[source]
Finds an XML sub-element of specified type, adding a default element of that type if necessary.
- Parameters:
- Return type:
- Returns:
An
ElementTree.Element
, of typesub_element_type
, which is a child of the argument element that either (a) one which existed before the function call or (b) the root of a new, default subtree.
sub-elements of given type.
- class dair_pll.urdf_utils.UrdfGeometryRepresentationFactory[source]
Bases:
object
Utility class for generating URDF representations of
CollisionGeometry
instances.- static representation(geometry, output_dir)[source]
Representation of an associated URDF tag that describes the properties of this geometry.
Tags are expected to be put inside a
<collision>
tag in the URDF file.Example
To output
<sphere radius="5.1">
for aSphere
, return the following:('sphere', {'radius': '5.1'})
- static box_representation(box)[source]
Returns URDF representation as
box
tag with full-length sizes.
- dair_pll.urdf_utils.fill_link_with_parameterization(element, pi_cm, geometries, friction_coeffs, output_dir)[source]
Convert pytorch inertial and geometric representations to URDF elements.
- Parameters:
element (
Element
) – XML “link” tag in which representation is stored.pi_cm (
Tensor
) – (10,) inertial representation of link inpi_cm
parameterization.geometries (
List
[CollisionGeometry
]) – All geometries attached to body.friction_coeffs (
Tensor
) – All friction coefficients associated with each geometry. TheTensor
will be of shape(len(geometries),)
.output_dir (
str
) – File directory to store helper files (e.g., meshes).
Warning
Does not handle multiple geometries.
- Raises:
NotImplementedError – when multiple geometries are provided.
- Return type:
- dair_pll.urdf_utils.represent_multibody_terms_as_urdfs(multibody_terms, output_dir)[source]
Renders the current parameterization of multibody terms as a set of urdfs.
- Parameters:
multibody_terms (
MultibodyTerms
) – Multibody dynamics representation to convert.output_dir (
str
) – File directory to store helper files (e.g., meshes).
- Return type:
- Returns:
Dictionary of (urdf name, urdf XML string) pairs.
Warning
For now, assumes that each URDF link element
e
gets modeled as a corresponding bodyb
withb.name() == e.get("name")
. Drake however does not guarantee this relationship. A more stable implementation would be to directly edit the MultibodyPlant, but this would make the representation less portable.