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. Without a SceneGraph, deformable models will also be ignored.
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 basic 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 here, but the parser does log warnings for any unsupported MuJoCo XML elements or attributes at runtime.
The MuJoCo camera element is supported (with any unsupported attributes emitting the standard parser warnings). To parse cameras, you must register a DiagramBuilder with the Parser, and the MultibodyPlant must have a registered SceneGraph. The parser will call ApplyCameraConfig() to produce a camera named "{model_instance_name}/{mjcf_camera_name}", where a default {mjcf_camera_name} of "camera{i}" for the ith camera (starting from 0) will be provided if no name is specified in the xml. Note that calling MultibodyPlant::RenameModelInstance after parsing will not update the camera name.
The following attributes are specific to the MuJoCo solver (listed here in the order they are listed in the MuJoCo documentation); we have no plans to support them:
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:
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 specifying deformable bodies through SDFormat via custom tags as an experimental feature. A <link> element is interpreted as a deformable body if it contains a <drake:deformable_properties> element (see drake:deformable_properties). In that case, there are several requirements that must be satisfied:
Violating any of these rules results in a parsing error.
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:
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:
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.
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.
Specifying this tag for a visual whose perception role has been disabled will emit a warning.
Specifies the angle of a circular by right-hand-rule. Units are radians.
The element adds a ball constraint to the model via drake::multibody::MultibodyPlant::AddBallConstraint().
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.
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.
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.
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.
The element adds a tendon constraint to the model via drake::multibody::MultibodyPlant::AddTendonConstraint().
The string names a joint (expected to already be defined by this model and be single-dof) and the float specifies a coefficient to be applied to the joint configuration to determine the tendon length. These will be passed to drake::multibody::MultibodyPlant::AddTendonConstraint() as the joints and a parameters, respectively. The tag can be repeated to specify multiple joints.
A floating point value specifying the length offset in either [m] or [rad] that will be passed to drake::multibody::MultibodyPlant::AddTendonConstraint() as the offset parameter.
A floating point value specifying the lower bound on the constraint in either [m] or [rad] that will be passed to drake::multibody::MultibodyPlant::AddTendonConstraint() as the lower_bound parameter.
A floating point value specifying the upper bound on the constraint in either [m] or [rad] that will be passed to drake::multibody::MultibodyPlant::AddTendonConstraint() as the upper_bound parameter.
A floating point value specifying the constraint stiffness in either [N/m] or [N⋅m/rad] that will be passed to drake::multibody::MultibodyPlant::AddTendonConstraint() as the stiffness parameter.
A floating point value specifying the constraint damping in either [N⋅s/m] or [N⋅m⋅rad/s] that will be passed to drake::multibody::MultibodyPlant::AddTendonConstraint() as the damping parameter.
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.
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.
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.
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.
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.
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.
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.
The string names a frame (defined elsewhere in the model) that is associated with the child link of the joint being defined.
A joint-type-specific tag for drake::multibody::CurvilinearJoint, corresponding to a drake:joint of curvilinear type.
This element specifies a circular arc along which the joint moves. The initial position and orientation of the segment are defined by the drake:initial_tangent and drake:plane_normal tags on the joint and previous segments in the joint's drake:curves list.
The circular arc rotates about the plane normal axis, with a turning angle and radius specified directly in the tag by right hand rule.
For URDF, these values are contained in the radius and angle attributes of the element. For SDF, drake:radius and drake:angle child elements contain the values.
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()).
If present, this element sets the compliance type of the element being defined to be compliant, as opposed to rigid, in hydroelastic contact models.
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.
A joint-type-specific tag for drake::multibody::CurvilinearJoint, corresponding to a drake:joint of curvilinear type.
Curvilinear joints allow the child frame to move relative to the parent along a planar curvilinear path, expressed in this tag as an ordered list of linear and circular arc segments. Each segment is appended to the end of the previous segment, so that the entire path is continuously differentiable.
The initial heading of the curve is determined by the joint's drake:initial_tangent element, and remains in a plane defined by the joint's drake:plane_normal.
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.
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.
If present, this element defines the link element as a deformable body in Drake. Such link elements are not treated as rigid bodies, and the standard tags such as inertia are illegal and provoke errors. The only other tags that are allowed are under such "deformable" links are <pose>, <collision>, and <visual>. Attaching frames, joints, and other elements to deformable links is not allowed. The <pose> tag is interpreted as the pose of the deformable geometry used for dynamics and collision in its reference configuration. The <collision> and <visual> tags are not interpreted exactly the same way as the standard <collision> and <visual> tags either. We explain the differences in the Deformable link requirements section.
The following nested elements may be present under <drake:deformable_properties>:
see drake:youngs_modulus drake:poissons_ratio drake:mass_damping drake:stiffness_damping drake:mass_density drake:material_model
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.
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.
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.
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).
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).
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).
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.
<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.
A joint-type-specific tag for drake::multibody::CurvilinearJoint, corresponding to a drake:joint of curvilinear type.
For curvilinear joints, this element provides the tangent vector, in parent frame coordinates, of the curvilinear path along which the joint moves at joint position 0.
A joint-type-specific tag for drake::multibody::CurvilinearJoint, corresponding to a drake:joint of curvilinear type.
Curvilinear joints can be periodic, allowing the joint to travel multiple laps along the curvilinear path of the joint without hitting joint limits. This element specifies whether this behavior is enabled (true) or not.
For SDF, the value true or false is specified as the content of the tag. For URDF, the value is expressed as the value attribute of the tag.
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 supported type values are curvilinear and planar. The element must contain nested drake:parent, drake:child, and drake:damping elements.
In URDF, supported type values are one of ball, curvilinear, planar, screw or universal. The nested elements are the same as those defined by the standard joint element with the exception of the screw and curvilinear joint types. screw joints requires a nested drake:screw_thread_pitch element. curvilinear joints require a full geometric definition of a planar curvilinear path along which the joint moves, specified as the following:
Specifies length of a line segment in meters.
A joint-type-specific tag for drake::multibody::CurvilinearJoint, corresponding to a drake:joint of curvilinear type.
This element specifies a line segment along which the joint moves. The initial position and orientation of the segment are defined by the drake:initial_tangent and drake:plane_normal tags on the joint and previous segments in the joint's drake:curves list.
The length of the segment is expressed in the tag directly. For URDF, this value is contained in the length attribute of the element, while for SDF, this value is contained in a drake:length child element.
This element adds a drake::multibody::LinearBushingRollPitchYaw to the model.
If present, this element provides a value (with unit 1/s) for the mass damping coefficient in Rayleigh damping for the deformable body.
If present, this element provides a value (with unit kg/m³) for the mass density of the deformable body.
If present, this element provides the material model of the deformable body. The valid values are linear_corotated, corotated, and linear.
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.
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.
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.
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.
The provided (dimensionless) value sets the dynamic friction parameter for CoulombFriction. Refer to Continuous Approximation of Coulomb Friction for details on the friction model.
The provided (dimensionless) value sets the static friction parameter for CoulombFriction. Refer to Continuous Approximation of Coulomb Friction for details on the friction model.
<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.
A joint-type-specific tag for drake::multibody::CurvilinearJoint, corresponding to a drake:joint of curvilinear type.
Curvilinear joints allow the child frame to move relative to the parent along a curvilinear path which lies in a plane in parent frame. This element provides the normal vector, in parent frame coordinates.
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).
If present, this element provides a value (unitless) for the Poisson's ratio for for the deformable body.
If present, this element defines proximity properties for the parent link. The following nested elements may be present:
Specifies the radius of a circular arc. Units are meters.
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).
If present, this element sets the compliance type of the element being defined to be rigid, as opposed to compliant, in hydroelastic contact models.
Applies the indicated rotor inertia value to the appropriate JointActuator object. Units are kg⋅m² for revolute joints, and kg for prismatic joints.
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.
If present, this element provides a value (with unit s) for the stiffness damping coefficient in Rayleigh damping for the deformable body.
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:
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.
If present, this element specifies a wall boundary condition for a deformable body. The wall boundary condition constrains vertices of the deformable body's mesh to have zero displacement if their reference positions are inside a prescribed open half space. The half space is defined by a plane with an outward normal vector.
The nested elements are:
Multiple drake:wall_boundary_condition elements can be specified for a single deformable link to define multiple boundary conditions. This element is only valid for deformable links (those containing a drake:deformable_properties element).
If present, this element provides a value (with unit Pa(N/m²)) for the Young's modulus for the deformable body.