Drake
Drake C++ Documentation
Parsing Models for Multibody Dynamics

Drake's drake::multibody::Parser accepts model files written in either SDFormat or URDF.

In both formats, however, there are Drake-specific extensions and Drake-specific limitations.

The result of the parse is an in-memory model realized within drake::multibody::MultibodyPlant and (optionally) drake::geometry::SceneGraph. Note that parses that do not use a SceneGraph will effectively ignore geometric model elements, especially //visual and //collision elements.

In the reference sections below, the relevant usage paths for various tags are indicated using XPath notation.

SDFormat Support

Drake supports SDFormat files following the specification at http://sdformat.org/spec. As of this writing, the supported spec version is 1.9, but check also the Drake release notes for current status.

For Drake extensions to SDFormat files, see Drake Extensions.

Drake's parser does not implement all of the features of SDFormat. In the future, we intend to update this documentation to itemize what isn't supported.

SDFormat model composition

Drake's SDFormat parsing supports composing multiple models into a single model, via lexical nesting and file inclusion. The file inclusion feature supports both SDFormat files and URDF files. Note that included URDF files pass through the Drake URDF parser, with all of it's extensions and limitations.

For full details, see the SDFormat documentation of model composition.

An important feature of SDFormat model composition is the ability to cross-reference features of other models. Cross-references are denoted by using scoped names.

Scoped names

Scoped names allow referring to an element of a model nested within the current model. They take the form of some number of nested model names, plus the element name, all joined by the delimiter ::. Names not using the :: delimeter are not considered scoped names; they are used to define or refer to elements of the current model. For example, suppose that model A contains model B, which in turn contains model C. Here are some valid scoped names:

Note that (deliberately) there is no way to refer to elements outward or upward from the current model; all names are relative to the current model and can only refer to the current or a nested model. In particular, names must not start with ::; there is no way to denote any "outer" or "outermost" scope.

For a detailed design discussion with examples, see the SDFormat documentation of name scoping.

URDF Support

Drake supports URDF files as described here: http://wiki.ros.org/urdf/XML.

For Drake extensions to URDF format files, see Drake Extensions.

URDF not supported by Drake

Drake's parser does not implement all of the features of URDF. Here is a list of known URDF features that Drake does not use. For each, the parser applies one of several treaments:

Tags that provoke a warning

Tags ignored silently

Tags given special treatment.

Both versions of mechanicalReduction will be silently ignored if the supplied value is 1; otherwise the they will provoke a warning that the value is being ignored.

Drake Extensions

Drake extends both SDFormat and URDF in similar ways, to allow access to Drake-specific features. This section provides a compact reference to all Drake extensions and their use in both formats.

Note that in both formats, it is proper to declare the drake: namespace prefix. For SDFormat, declare it like this:

<sdf xmlns:drake="http://drake.mit.edu" version="1.9">

For URDF, declare the namespace prefix like this:

<robot xmlns:drake="http://drake.mit.edu" name="test_robot">

Here is the full list of custom elements:

drake:acceleration

Semantics

If the joint type is one of (continuous, prismatic, revolute), specifies acceleration limits of (-VALUE, +VALUE). Units are determined by the type of joint, either radians/sec^2 for continuous and revolute joints, or m/s^2 for prismatic joints.

drake:accepting_renderer

Semantics

The tag serves as a list of renderers for which this visual is targeted.

This feature is one way to provide multiple visual representations of a body.

drake:bushing_force_damping

Semantics

The three floating point values (units of N⋅s/m) are formed into a vector and passed to the constructor of drake::multibody::LinearBushingRollPitchYaw as the force_damping_constants parameter.

See also
drake:linear_bushing_rpy, drake::multibody::LinearBushingRollPitchYaw, How to choose force stiffness and damping constants

drake:bushing_force_stiffness

Semantics

The three floating point values (units of N/m) are formed into a vector and passed to the constructor of drake::multibody::LinearBushingRollPitchYaw as the force_stiffness_constants parameter.

See also
drake:linear_bushing_rpy, drake::multibody::LinearBushingRollPitchYaw, How to choose force stiffness and damping constants

drake:bushing_frameA

Semantics

The string names a frame (expected to already be defined by this model) that will be passed to the constructor of drake::multibody::LinearBushingRollPitchYaw as the frameA parameter.

See also
drake:linear_bushing_rpy, drake::multibody::LinearBushingRollPitchYaw

drake:bushing_frameC

Semantics

The string names a frame (expected to already be defined by this model) that will be passed to the constructor of drake::multibody::LinearBushingRollPitchYaw as the frameC parameter.

See also
drake:linear_bushing_rpy, drake::multibody::LinearBushingRollPitchYaw

drake:bushing_torque_damping

Semantics

The three floating point values (units of N⋅m⋅s/rad) are formed into a vector and passed to the constructor of drake::multibody::LinearBushingRollPitchYaw as the torque_damping_constants parameter.

See also
drake:linear_bushing_rpy, drake::multibody::LinearBushingRollPitchYaw, How to choose torque stiffness and damping constants

drake:bushing_torque_stiffness

Semantics

The three floating point values (units of N⋅m/rad) are formed into a vector and passed to the constructor of drake::multibody::LinearBushingRollPitchYaw as the torque_stiffness_constants parameter.

See also
drake:linear_bushing_rpy, drake::multibody::LinearBushingRollPitchYaw, How to choose torque stiffness and damping constants

drake:capsule

Semantics

Constructs a drake::geometry::Capsule of the given radius (meters) and length (meters), and adds it to either the visual or collision geometry of the model.

SDFormat note: drake:capsule is proposed for deprecation; see issue #14387.

URDF note: Drake supports both drake:capsule, and a non-standard (non-prefixed) capsule tag with the same syntax and semantics.

drake:child

Semantics

The string names a frame (defined elsewhere in the model) that is associated with the child link of the joint being defined.

See also
drake:joint

drake:collision_filter_group

Semantics

This element names a group of bodies to participate in collision filtering rules. If the ignore attribute is present and true-valued, the entire element is skipped during parsing. The nested elements must included one or more drake:member elements, and zero or more drake:ignored_collision_filter_group elements.

This element defines a new group name that is only available during parsing. It must not be a scoped name.

Collision filtering rules are only constructed with pairs of groups, where both sides of the pair may name the same group. The drake:ignored_collision_filter_group element establishes a pairing between the group it names and the group within which it is nested. A pair containing different collision groups excludes collisions between members of those groups (see drake::geometry::CollisionFilterDeclaration::ExcludeBetween()). A pair naming the same group twice excludes collisions within the group (see drake::geometry::CollisionFilterDeclaration::ExcludeWithin()).

See also
drake:member, drake:ignored_collision_filter_group, Scoped names

drake:compliant_hydroelastic

Semantics

If present, this element sets the compliance type of the element being defined to be compliant, as opposed to rigid, in hydroelastic contact models.

See also
drake:proximity_properties, Creating hydroelastic representations of collision geometries

drake:damping

Semantics

If the parent joint type is planar, construct a vector from the values (units of (N⋅s/m, N⋅s/m, N⋅m⋅s) respectively) and pass it to the damping parameter of the constructor of drake::multibody::PlanarJoint. The first two values are for translation; the third is for rotation. See that class for discussion of units and detailed semantics.

URDF Note: The comparable feature in URDF is the standard /robot/link/joint/dynamics/@damping attribute.

drake:declare_convex

Semantics

If present, this element causes Drake to treat the parent mesh geometry as convex, without any further validation. The resulting geometry in memory will be drake::geometry::Convex, rather than drake::geometry::Mesh.

See also
drake::geometry::Convex, drake::geometry::Mesh

drake:diffuse_map

Semantics

If present, this element indicates (by filename or package: URI) a PNG file to use as a diffuse texture map. The resolved path name is stored in a PerceptionProperties object under (phong, diffuse_map).

See also
drake::geometry::PerceptionProperties, drake::multibody::PackageMap, Geometry perception properties

drake:ellipsoid

Semantics

Constructs a drake::geometry::Ellipsoid with the given half-axis length parameters a, b, and c (all in units of meters), and adds it to either the visual or collision geometry of the model.

drake:gear_ratio

Semantics

Applies the indicated gear ratio value to the appropriate JointActuator object. This value is only used for reflected inertia calculations, and not as a torque multiplier. The value is dimensionless for revolute joints, and has units of 1/m for prismatic joints.

See also
drake::multibody::JointActuator, drake:rotor_inertia, Reflected Inertia

drake:hunt_crossley_dissipation

Semantics

If present, this element provides a value (units of inverse of velocity, i.e. s/m) for the Hunt-Crossley dissipation model. It is stored in a ProximityProperties object under (material, hunt_crossley_dissipation).

See also
drake::geometry::ProximityProperties, Hydroelastic contact, Modeling Dissipation

drake:hydroelastic_modulus

Semantics

If present, this element provides a value (units of pressure, i.e. Pa (N/m²)) for the hydroelastic modulus. It is stored in a ProximityProperties object under (hydroelastic, hydroelastic_modulus).

See also
drake::geometry::ProximityProperties, Hydroelastic contact, Properties for hydroelastic contact

drake:ignored_collision_filter_group

Semantics

The string names a collision filter group that will be paired with the parent group when constructing filtering rules. It may name the parent group.

In SDFormat files only, the name may refer to a group within a nested model (either URDF or SDFormat) by using a scoped name.

See also
drake:collision_filter_group, Scoped names

drake:joint

Semantics

In both formats, the drake:joint element is used as a substitute for standard joint elements, to allow support for non-standard joint types. The overall semantics are the same as for a standard joint.

In SDFormat, the only supported type value is planar. The element must contain nested drake:parent, drake:child, and drake:damping elements.

In URDF, supported type values are one of ball, planar, or universal. The nested elements are the same as those defined by the standard joint element.

See also
drake:parent, drake:child, drake:damping

drake:linear_bushing_rpy

Semantics

This element adds a drake::multibody::LinearBushingRollPitchYaw to the model.

See also
drake::multibody::LinearBushingRollPitchYaw, drake:bushing_force_damping, drake:bushing_force_stiffness, drake:bushing_frameA, drake:bushing_frameC, drake:bushing_torque_damping, drake:bushing_torque_stiffness

drake:member

Semantics

This element names a link (defined elsewhere in the model) to be a member of the parent collision filter group.

In SDFormat files only, the name may refer to a link within a nested model (either URDF or SDFormat) by using a scoped name.

See also
drake:collision_filter_group, Scoped names

drake:mesh_resolution_hint

Semantics

The provided value (in units of meters) helps select the resolution of meshes generated from geometric primitives (sphere, cylinder, capsule, etc.). The exact semantics depend on the geometry being generated. Within some practical limits, smaller values will select shorter edge lengths and a finer mesh, larger values will select longer edge lengths and a coarser mesh.

See also
drake:proximity_properties, Properties for hydroelastic contact

drake:mu_dynamic

Semantics

The provided (dimensionless) value sets the dynamic friction parameter for CoulombFriction. Refer to Continuous Approximation of Coulomb Friction for details on the friction model.

See also
drake:proximity_properties, drake::multibody::CoulombFriction, Continuous Approximation of Coulomb Friction

drake:mu_static

Semantics

The provided (dimensionless) value sets the static friction parameter for CoulombFriction. Refer to Continuous Approximation of Coulomb Friction for details on the friction model.

Warning
This value is ignored when modeling the multibody system with discrete dynamics, refer to MultibodyPlant's constructor documentation for details, in particular the parameter time_step.
See also
drake:proximity_properties, drake::multibody::CoulombFriction, Continuous Approximation of Coulomb Friction

drake:parent

Semantics

The string names a frame (defined elsewhere in the model) that is associated with the parent link of the joint being defined.

See also
drake:joint

drake:point_contact_stiffness

Semantics

If present, this element provides a stiffness value (units of N/m) for point contact calculations for this specific geometry. It is stored in a ProximityProperties object under (material, point_contact_stiffness).

See also
accessing_contact_properties, mbp_penalty_method, drake::geometry::ProximityProperties

drake:proximity_properties

Semantics

If present, this element defines proximity properties for the parent link. The following nested elements may be present:

See also
drake:compliant_hydroelastic, drake:hunt_crossley_dissipation, drake:hydroelastic_modulus, drake:mesh_resolution_hint, drake:mu_dynamic, drake:mu_static, drake:point_contact_stiffness, drake:rigid_hydroelastic, drake::geometry::ProximityProperties

drake:relaxation_time

Semantics

If present, this element provides a value (units of time, i.e. seconds) for a linear Kelvin-Voigt model of dissipation. It is stored in a ProximityProperties object under (material, relaxation_time).

See also
drake::geometry::ProximityProperties, Modeling Dissipation

drake:rigid_hydroelastic

Semantics

If present, this element sets the compliance type of the element being defined to be rigid, as opposed to compliant, in hydroelastic contact models.

See also
drake:proximity_properties, Creating hydroelastic representations of collision geometries

drake:rotor_inertia

Semantics

Applies the indicated rotor inertia value to the appropriate JointActuator object. Units are kg⋅m² for revolute joints, and kg for prismatic joints.

See also
drake::multibody::JointActuator, drake:gear_ratio, Reflected Inertia