Drake's drake::multibody::Parser accepts model files written in a variety of input formats.
Drake's parsing of URDF, SDFormat, and MJCF (Mujoco XML) has Drake-specific extensions and 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, when discussing XML formats, the relevant usage paths for various tags are indicated using XPath notation.
Drake Model Directives is a Drake-native model description format, primarily intended for combining models written in other formats into complex scenes. It is YAML based, and follows a limited data schema. See multibody/parsing/README_model_directives.md
for more detail.
There is limited, undocumented support for parsing MJCF (Mujoco XML) files. The files are recognized by an .xml file extension. The scope of features that are actually supported still need to be documented.
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.
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 its 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 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 ::
delimiter 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:
some_frame_in_A
B::some_frame_in_B
B::C::some_frame_in_C
some_frame_in_B
C::some_frame_in_C
some_frame_in_C
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.
Drake supports URDF files as described here: http://wiki.ros.org/urdf/XML.
For Drake extensions to URDF format files, see Drake Extensions.
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 treatments:
/robot/@version
/robot/joint/calibration
/robot/joint/safety_controller
/robot/link/@type
/robot/link/collision/verbose
/robot/transmission/@name
/robot/transmission/flexJoint
/robot/transmission/gap_joint
/robot/transmission/leftActuator
/robot/transmission/passive_joint
/robot/transmission/rightActuator
/robot/transmission/rollJoint
/robot/transmission/use_simulated_gripper_joint
/robot/gazebo
/robot/transmission/actuator/hardwareInterface
/robot/transmission/joint/hardwareInterface
/robot/transmission/actuator/mechanicalReduction
/robot/transmission/mechanicalReduction
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 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:
//model/joint/axis/limit/drake:acceleration
/robot/joint/limit/@drake:acceleration
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.
//model/link/visual/drake:accepting_renderer
/robot/link/visual/drake:accepting_renderer/@name
The tag serves as a list of renderers for which this visual is targeted.
<drake:accepting_renderer>
every renderer will be given the chance to reify this visual geometry.This feature is one way to provide multiple visual representations of a body.
Specifying this tag for a visual whose perception role has been disabled will emit a warning.
//model/drake:ball_constraint
/robot/drake:ball_constraint
The element adds a ball constraint to the model via drake::multibody::MultibodyPlant::AddBallConstraint().
//model/drake:ball_constraint/drake:ball_constraint_body_A
/robot/drake:ball_constraint/drake:ball_constraint_body_A/@name
The string names a body (expected to already be defined by this model) that will be passed to drake::multibody::MultibodyPlant::AddBallConstraint() as the body_A
parameter.
//model/drake:ball_constraint/drake:ball_constraint_body_B
/robot/drake:ball_constraint/drake:ball_constraint_body_B/@name
The string names a body (expected to already be defined by this model) that will be passed to drake::multibody::MultibodyPlant::AddBallConstraint() as the body_B
parameter.
//model/drake:ball_constraint/drake:ball_constraint_p_AP
/robot/drake:ball_constraint/drake:ball_constraint_p_AP/@value
The three floating point values (units of meters) are formed into a vector and passed into drake::multibody::MultibodyPlant::AddBallConstraint() as the p_AP
parameter.
//model/drake:ball_constraint/drake:ball_constraint_p_BQ
/robot/drake:ball_constraint/drake:ball_constraint_p_BQ/@value
The three floating point values (units of meters) are formed into a vector and passed into drake::multibody::MultibodyPlant::AddBallConstraint() as the p_BQ
parameter.
//model/drake:linear_bushing_rpy/drake:bushing_force_damping
/robot/drake:linear_bushing_rpy/drake:bushing_force_damping/@value
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.
//model/drake:linear_bushing_rpy/drake:bushing_force_stiffness
/robot/drake:linear_bushing_rpy/drake:bushing_force_stiffness/@value
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.
//model/drake:linear_bushing_rpy/drake:bushing_frameA
/robot/drake:linear_bushing_rpy/drake:bushing_frameA/@name
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.
//model/drake:linear_bushing_rpy/drake:bushing_frameC
/robot/drake:linear_bushing_rpy/drake:bushing_frameC/@name
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.
//model/drake:linear_bushing_rpy/drake:bushing_torque_damping
/robot/drake:linear_bushing_rpy/drake:bushing_torque_damping/@value
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.
//model/drake:linear_bushing_rpy/drake:bushing_torque_stiffness
/robot/drake:linear_bushing_rpy/drake:bushing_torque_stiffness/@value
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.
//geometry[parent::visual|parent::collision]/drake:capsule
//geometry[parent::visual|parent::collision]/drake:capsule
radius
and length
, each of which contain a non-negative floating point value.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.
//model/drake:joint/drake:child
The string names a frame (defined elsewhere in the model) that is associated with the child link of the joint being defined.
//model/drake:collision_filter_group
/robot/drake:collision_filter_group
name
(string) and ignore
(boolean); nested elements drake:member
, drake:member_group
, and drake:ignored_collision_filter_group
.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
or drake:member_group
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()).
//model/link/collision/drake:proximity_properties/drake:compliant_hydroelastic
/robot/link/collision/drake:proximity_properties/drake:compliant_hydroelastic
If present, this element sets the compliance type of the element being defined to be compliant, as opposed to rigid, in hydroelastic contact models.
//model/joint/drake:controller_gains
/robot/joint/actuator/drake:controller_gains
p
(proportional gain) containing a positive floating point value and d
(derivative gain) containing a non-negative floating point value.If present, this element provides proportional and derivative gains for a low level PD controller for the drake::multibody::JointActuator associated with the drake::multibody::Joint the element is defined under. It is stored in a drake::multibody::PdControllerGains object in the drake::multibody::JointActuator class. Both attributes p
and d
are required.
//model/drake:joint/drake:damping
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/joint/dynamics/@damping
attribute.
//geometry[parent::visual|parent::collision]/mesh/drake:declare_convex
//geometry[parent::visual|parent::collision]/mesh/drake:declare_convex
If present, this element causes Drake to use the convex hull of the named mesh geometry. The resulting geometry in memory will be drake::geometry::Convex, rather than drake::geometry::Mesh.
//model/link/visual/material/drake:diffuse_map
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)
. URDF provides a built-in tag, i.e., //robot/material/texture
or //robot/link/visual/material/texture
, to specify a diffuse texture map for a link.
//geometry[parent::visual|parent::collision]/drake:ellipsoid
//geometry[parent::visual|parent::collision]/drake:ellipsoid
a
, b
, c
, each of which contain a positive floating point value.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.
//model/joint/drake:gear_ratio
/robot/joint/actuator/drake:gear_ratio@value
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.
//model/link/collision/drake:proximity_properies/drake:hunt_crossley_dissipation
/robot/link/collision/drake:proximity_properties/drake:hunt_crossley_dissipation/@value
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)
.
//model/link/collision/drake:proximity_properties/drake:hydroelastic_margin
/robot/link/collision/drake:proximity_properties/drake:hydroelastic_margin/@value
If present, this element provides a value (units of length, i.e. m) for the hydroelastic margin. It is stored in a ProximityProperties object under (hydroelastic, margin)
.
//model/link/collision/drake:proximity_properties/drake:hydroelastic_modulus
/robot/link/collision/drake:proximity_properties/drake:hydroelastic_modulus/@value
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)
.
//model/drake:collision_filter_group/drake:ignored_collision_filter_group
/robot/drake:collision_filter_group/drake:ignored_collision_filter_group/@name
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.
//model/link/visual/drake:illustration_properties
enabled
(bool).<visual>
geometries are assigned illustration roles by default. Their appearance in visualizers reflect the materials associated with the <visual>
tag (or, as for meshes, the materials associated with the mesh). If no materials are defined, then they pick up whatever default materials the visualizers define. A <visual>
tag can opt out of the illustration role by setting the enabled
attribute to false
. Setting it to true
is equivalent to omitting the tag completely.
Note: if a <visual>
tag has disabled both illustration properties and perception properties, a warning will be emitted. Essentially, the model defines a geometry that would be consumed by typical loaders, but it has been completely disabled for Drake. The definition for Drake should refine the more generic model, but it shouldn't consist of an arbitrarily different set of visuals.
//model/drake:joint
/robot/drake:joint
name
(string) and type
(choice: see below), and nested elements (see below).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
, screw
or universal
. The nested elements are the same as those defined by the standard joint element with the exception of the screw
joint type, which requires a nested drake:screw_thread_pitch
element.
//model/drake:linear_bushing_rpy
/robot/drake:linear_bushing_rpy
drake:bushing_frameA
, drake:bushing_frameC
, drake:bushing_torque_stiffness
, drake:bushing_torque_damping
, drake:bushing_force_stiffness
, and drake:bushing_force_damping
.This element adds a drake::multibody::LinearBushingRollPitchYaw to the model.
//model/drake:collision_filter_group/drake:member
/robot/drake:collision_filter_group/drake:member/@link
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.
//model/drake:collision_filter_group/drake:member_group
/robot/drake:collision_filter_group/drake:member_group/@name
This element names a collision filter group (defined elsewhere in the model), all of whose members become members 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.
//model/link/collision/drake:proximity_properties/drake:mesh_resolution_hint
/robot/link/collision/drake:proximity_properties/drake:mesh_resolution_hint/@value
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.
//model/joint/drake:mimic
joint
(string), multiplier
(double) and offset
(double)This tag has equivalent semantics to those of the native URDF <mimic> tag. If q0
is the position of the <joint>
and q1
the position of the joint specified by the joint
attribute, the two joints are constrained to enforce the relation: q0 = multiplier * q1 + offset
. The units of multiplier
and offset
depend on the type of joints specified. This tag only supports single degree of freedom joints that exist in the same model instance.
//model/link/collision/drake:proximity_properties/drake:mu_dynamic
/robot/link/collision/drake:proximity_properties/drake:mu_dynamic/@value
The provided (dimensionless) value sets the dynamic friction parameter for CoulombFriction. Refer to Continuous Approximation of Coulomb Friction for details on the friction model.
//model/link/collision/drake:proximity_properties/drake:mu_static
/robot/link/collision/drake:proximity_properties/drake:mu_static/@value
The provided (dimensionless) value sets the static friction parameter for CoulombFriction. Refer to Continuous Approximation of Coulomb Friction for details on the friction model.
mu_dynamic
and mu_static
are used by MultibodyPlant when the plant time_step=0
, but only mu_dynamic
is used when time_step>0
. Refer to MultibodyPlant's constructor documentation for details.//model/drake:joint/drake:parent
//model/link/visual/drake:perception_properties
enabled
(bool).<visual>
geometries are assigned perception roles by default. Their appearance in renderers reflect the materials associated with the <visual>
tag (or, as for meshes, the materials associated with the mesh). If no materials are defined, then they pick up whatever default materials the renderers define. A <visual>
tag can opt out of the perception role by setting the enabled
attribute to false
. Setting it to true
is equivalent to omitting the tag completely.
Note: if a <visual>
tag has disabled both perception properties and illustration properties, a warning will be emitted. Essentially, the model defines a geometry that would be consumed by typical loaders, but it has been completely disabled for Drake. The definition for Drake should refine the more generic model, but it shouldn't consist of an arbitrarily different set of visuals.
The string names a frame (defined elsewhere in the model) that is associated with the parent link of the joint being defined.
//model/link/collision/drake:proximity_properties/drake:point_contact_stiffness
/robot/link/collision/drake:proximity_properties/drake:point_contact_stiffness/@value
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)
.
//model/link/collision/drake:proximity_properties
/robot/link/collision/drake:proximity_properties
If present, this element defines proximity properties for the parent link. The following nested elements may be present:
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
//model/link/collision/drake:proximity_properies/drake:relaxation_time
/robot/link/collision/drake:proximity_properties/drake:relaxation_time/@value
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)
.
//model/link/collision/drake:proximity_properties/drake:rigid_hydroelastic
/robot/link/collision/drake:proximity_properties/drake:rigid_hydroelastic
If present, this element sets the compliance type of the element being defined to be rigid, as opposed to compliant, in hydroelastic contact models.
//model/joint/drake:rotor_inertia
/robot/joint/actuator/drake:rotor_inertia@value
Applies the indicated rotor inertia value to the appropriate JointActuator object. Units are kg⋅m² for revolute joints, and kg for prismatic joints.
//model/joint/screw_thread_pitch
/robot/joint/actuator/drake:screw_thread_pitch@value
Applies the indicated thread pitch value to the appropriate ScrewJoint object. This kinematic parameter specifies the axial distance traveled for each revolution of the joint. Units are m/revolution, with a positive value corresponding to a right-handed thread.
//model/link
<visual>
tag, but with the drake
namespace prepended. All tags that can be found under the <visual>
tag (e.g., <pose>
, <geometry>
, <sphere>
, etc.) can be included under the <drake:visual>
tag, provided they have the drake
namespace affixed (e.g., <drake:pose>
, <drake:geometry>
, <drake:sphere>
, etc.).The <drake:visual>
tag is provided for the purpose of defining visual elements that only Drake will consume. This could be used to do Drake-specific augmentation of a model. But the main intended use case is for associating different geometries with a link based on its role. Use one geometry for the illustration role and another for the perception role. To use different geometries per role:
<visual>
tag for that default geometry (including all typical descendant tags).<visual>
tag, include the <drake:??_properties>
tag of the role this visual should not serve. Set its enabled
attribute to false
. Remember, by default the visual would get both roles, so you have to opt out of the role you don't want the geometry to have.<visual>
, add a <drake:visual>
tag and define its subtree as you normally would (making sure to prefix everything with the drake:
namespace).<drake:visual>
tag, include the other <drake:??_properties>
tag and set its enabled
tag to false
.This will allow Drake to use different visual representations for each visual role but still keep a more general SDFormat definition for other loaders.
Note: disabling both visual roles on a <drake:visual>
element will not emit a warning as it would for doing the same to a <visual>
tag.