pydrake.multibody.parsing

SDF and URDF parsing for MultibodyPlant and SceneGraph.

class pydrake.multibody.parsing.AddCollisionFilterGroup

Directive to add a collision filter group. This directive is analogous to tag_drake_collision_filter_group in XML model formats.

__init__(self: pydrake.multibody.parsing.AddCollisionFilterGroup, **kwargs) None
property ignored_collision_filter_groups

Names of groups against which to ignore collisions. If another group is named, collisions between this group and that group will be ignored. If this group is named, collisions within this group will be ignored. Names may be scoped and refer to other groups defined elsewhere in this file or transitively included directives or model files. This data is analogous to a sequence of tag_drake_ignored_collision_filter_group in XML model formats.

property member_groups

Names of groups to add en masse as members of the group. May be scoped and refer to bodies of already added models. This data is analogous to a sequence of tag_drake_member_group in XML model formats.

property members

Names of members of the group. May be scoped and refer to bodies of already added models. This data is analogous to a sequence of tag_drake_member in XML model formats.

property model_namespace

Optional model namespace. Allows name to be reused between models and lets you use the scoped name in ignored_collision_filter_groups.

property name

Name of group to be added. This is an unscoped name, and must be unique either globally or within its specified model namespace.

class pydrake.multibody.parsing.AddDirectives

Directive to incorporate another model directives file, optionally with its elements prefixed with a namespace.

__init__(self: pydrake.multibody.parsing.AddDirectives, **kwargs) None
property file

The package:// URI of the file to add.

property model_namespace

Namespaces base model instance for processing directive files. Affects scoping (i.e. the following members): - AddModel::name - AddModelInstance::name - AddFrame::name - AddWeld::parent - AddWeld::child - AddFrame::X_PF::base_frame - AddCollisionFilterGroup::name - AddCollisionFilterGroup::members - AddCollisionFilterGroup::ignored_colllision_filter_groups - AddDirectives::model_namespace See README.md for example references and namespacing.

class pydrake.multibody.parsing.AddFrame

Directive to add a Frame to the scene. The added frame must have a name and a transform with a base frame and offset.

__init__(self: pydrake.multibody.parsing.AddFrame, **kwargs) None
property name

Name of frame to be added. If scope is specified, will override model instance; otherwise, will use `X_PF.base_frame`s instance.

property X_PF

Pose of frame to be added, F, w.r.t. parent frame P (as defined by X_PF.base_frame).

class pydrake.multibody.parsing.AddModel

Directive to add a model from a URDF or SDFormat file to a scene, using a given name for the added instance.

__init__(self: pydrake.multibody.parsing.AddModel, **kwargs) None
property default_free_body_pose

Map of body_name or frame_name => default free body pose. The name must be a name within the scope of the model added by this directive. The name must not be scoped (i.e., no “foo::link”, just “link”).

However, the schema::Transform associated with that named body/frame can define a base_frame referring to any frame that has been added prior to or including this declaration. The named frame must always be a scoped name, even if its part of the model added by this directive.

Warning

if the transform’s base_frame is not the world (explicitly or implicitly by omission), the body associated with the named frame will not be considered a free body (body.is_floating() returns False) and calls to MultibodyPlant::SetDefaultFreeBodyPose() will have no effect on an allocated context. If you want to change its default pose after adding the model, you need to acquire the body’s joint and set the new default pose on the joint directly. Note: what you will actually be posing is the named frame. If it’s the name of the body, you will be posing the body. If it’s a frame affixed to the body frame, you will be posing the fixed frame (with the body offset based on the relationship between the two frames).

Warning

There should not already be a joint in the model between the two bodies implied by the named frames.

property default_joint_positions

Map of joint_name => default position vector. Each joint name must be a name within the scope of the model added by this directive. The name must not contains this model’s scoped name (nor that of any previously added model).

property file

The package:// URI of the file to add.

property name

The model instance name.

class pydrake.multibody.parsing.AddModelInstance

Directive to add an empty, named model instance to a scene.

__init__(self: pydrake.multibody.parsing.AddModelInstance, **kwargs) None
property name

The model instance name.

class pydrake.multibody.parsing.AddWeld

Directive to add a weld between two named frames, a parent and a child.

__init__(self: pydrake.multibody.parsing.AddWeld, **kwargs) None
property child

Child frame. Can (and should) specify scope.

property parent

Parent frame. Can specify scope.

property X_PC

Relative transform between the parent frame P and the child frame C. If unspecified, the Identity transform will be used.

pydrake.multibody.parsing.FlattenModelDirectives(directives: pydrake.multibody.parsing.ModelDirectives, package_map: pydrake.multibody.parsing.PackageMap) pydrake.multibody.parsing.ModelDirectives

Flatten model directives into a single object.

This function removes all AddDirectives directives from the given directives, locating the file via the given package_map, parsing it, and updating the names of its items to add any namespace prefix requested by the model_namespace of the directive. The resulting directives are appended to out.

The results of FlattenModelDirectives are semantically identical to directives. FlattenModelDirectives is therefore also idempotent.

This flattening is intended to assist with creating reproducible simulation scenarios and with hashing; it can also be useful in debugging.

pydrake.multibody.parsing.GetScopedFrameByName(plant: drake::multibody::MultibodyPlant<double>, full_name: str) drake::multibody::Frame<double>

Equivalent to GetScopedFrameByNameMaybe, but throws if the frame is not found.

pydrake.multibody.parsing.GetScopedFrameByNameMaybe(plant: drake::multibody::MultibodyPlant<double>, full_name: str) drake::multibody::Frame<double>

Finds an optionally model-scoped frame.

Returns nullptr if the frame is not found, as well as all the error cases of MultibodyPlant::HasFrameByName(std::string).

pydrake.multibody.parsing.LoadModelDirectives(filename: str) pydrake.multibody.parsing.ModelDirectives
pydrake.multibody.parsing.LoadModelDirectivesFromString(model_directives: str) pydrake.multibody.parsing.ModelDirectives
class pydrake.multibody.parsing.ModelDirective

Union structure for model directives.

Note

This was designed before support for std::variant<> was around, and thus we used a parent field, rather than a YAML tag, to designate the intended type for the directive.

__init__(self: pydrake.multibody.parsing.ModelDirective, **kwargs) None
property add_collision_filter_group
property add_directives
property add_frame
property add_model
property add_model_instance
property add_weld
class pydrake.multibody.parsing.ModelDirectives

Top-level structure for a model directives yaml file schema.

__init__(self: pydrake.multibody.parsing.ModelDirectives, **kwargs) None
property directives
class pydrake.multibody.parsing.ModelInstanceInfo

Convenience structure to hold all of the information to add a model instance from a file.

__init__(*args, **kwargs)
property child_frame_name

This is the unscoped frame name belonging to model_instance.

property model_instance
property model_name

Model name (possibly scoped).

property model_path

File path.

property parent_frame_name

This is the unscoped parent frame, assumed to be unique.

Type

WARNING

property X_PC
class pydrake.multibody.parsing.PackageMap

Maps ROS package names to their full path on the local file system. It is used by the SDF and URDF parsers when parsing files that reference ROS packages for resources like mesh files. This class can also download remote packages from the internet on an as-needed basis via AddRemote().

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.parsing.PackageMap) -> None

A constructor that initializes a default map containing only the top-level drake manifest. See PackageMap::MakeEmpty() to create an empty map.

  1. __init__(self: pydrake.multibody.parsing.PackageMap, other: pydrake.multibody.parsing.PackageMap) -> None

Copy constructor

Add(self: pydrake.multibody.parsing.PackageMap, package_name: str, package_path: str) None

Adds package package_name and its path, package_path. Throws if package_name is already present in this PackageMap with a different path, or if package_path does not exist.

AddMap(self: pydrake.multibody.parsing.PackageMap, other_map: pydrake.multibody.parsing.PackageMap) None

Adds all packages from other_map into this. Throws if other contains a package with the same package_name as one already in this map but with incompatible details (e.g., a different local path).

AddPackageXml(self: pydrake.multibody.parsing.PackageMap, filename: str) None

Adds an entry into this PackageMap for the given package.xml filename. Throws if filename does not exist or its embedded name already exists in this map.

AddRemote(self: pydrake.multibody.parsing.PackageMap, package_name: str, params: pydrake.multibody.parsing.PackageMap.RemoteParams) None
Contains(self: pydrake.multibody.parsing.PackageMap, package_name: str) bool

Returns true if and only if this PackageMap contains package_name.

GetPackageNames(self: pydrake.multibody.parsing.PackageMap) List[str]

Returns the package names in this PackageMap. The order of package names returned is unspecified.

GetPath(self: pydrake.multibody.parsing.PackageMap, package_name: str) str

Obtains the path associated with package package_name. Aborts if no package named package_name exists in this PackageMap.

Parameter deprecated_message:

When passed as nullptr (its default value), then in case the package_name is deprecated a deprecation message will be logged. When passed as non-nullptr the deprecation message will be output into this argument and will not be logged; if the package_name is not deprecated, the message will be set to nullopt.

static MakeEmpty() pydrake.multibody.parsing.PackageMap

A factory method that initializes an empty map.

PopulateFromEnvironment(self: pydrake.multibody.parsing.PackageMap, environment_variable: str) None

Obtains one or more paths from environment variable environment_variable. Crawls downward through the directory tree(s) starting from the path(s) searching for package.xml files. For each of these files, this method adds a new entry into this PackageMap where the key is the package name as specified within package.xml and the value is the path to the package.xml file. Multiple paths can be specified by separating them using the ‘:’ symbol. For example, the environment variable can contain [path 1]:[path 2]:[path 3] to search three different paths.

If a package already known by the PackageMap is found again with a conflicting path, a warning is logged and the original path is kept.

If a path does not exist or is unreadable, a warning is logged.

Warning

This function must not be used when populating manifests from the ROS_PACKAGE_PATH environment variable. It will throw an exception when that is attempted. Instead, use PopulateFromRosPackagePath().

PopulateFromFolder(self: pydrake.multibody.parsing.PackageMap, path: str) None

Crawls down the directory tree starting at path searching for directories containing the file package.xml. For each of these directories, this method adds a new entry into this PackageMap where the key is the package name as specified within package.xml and the directory’s path is the value. If a package already known by the PackageMap is found again with a conflicting path, a warning is logged and the original path is kept. If the path does not exist or is unreadable, a warning is logged.

PopulateFromRosPackagePath(self: pydrake.multibody.parsing.PackageMap) None

Obtains one or more paths from the ROS_PACKAGE_PATH environment variable. Semantics are similar to PopulateFromEnvironment(), except that ROS-style crawl termination semantics are enabled, which means that subdirectories of already-identified packages are not searched, and neither are directories which contain any of the following marker files: - AMENT_IGNORE - CATKIN_IGNORE - COLCON_IGNORE

class RemoteParams

Parameters used for AddRemote().

__init__(self: pydrake.multibody.parsing.PackageMap.RemoteParams, **kwargs) None
property archive_type

(Optional) The archive type of the downloaded file. Valid options are “zip”, “tar”, “gztar”, “bztar”, or “xztar”. By default, the archive type is determined from the file extension of the URL; in case the URL has no filename extension, you should explicitly specify one here.

property sha256

The cryptographic checksum of the file to be downloaded, as a 64-character hexadecimal string.

property strip_prefix

(Optional) A directory prefix to remove from the extracted files. In many cases, an archive will prefix all filenames with something like “package-v1.2.3/” so that it extracts into a convenient directory. This option will discard that common prefix when extracting the archive for the PackageMap. It is an error if the archive does not contain any diectory with this prefix, but if there are files outside of this directory they will be silently discarded.

ToJson(self: pydrake.multibody.parsing.PackageMap.RemoteParams) str

Returns the JSON serialization of these params.

property urls

The list of remote URLs for this resource. The urls are used in the other they appear here, so preferred mirror(s) should come first. Valid methods are “http://” or “https://” or “file://”.

Remove(self: pydrake.multibody.parsing.PackageMap, package_name: str) None

Removes package package_name and its previously added path. Throws if package_name is not present in this PackageMap.

ResolveUrl(self: pydrake.multibody.parsing.PackageMap, url: str) str

Returns a resolved path for url. URL schemes are either file:// for local files or package:// (or model://).

Raises

RuntimeError if the url cannot be resolved.

size(self: pydrake.multibody.parsing.PackageMap) int

Returns the number of entries in this PackageMap.

class pydrake.multibody.parsing.Parser

Parses model description input into a MultibodyPlant and (optionally) a SceneGraph. A variety of input formats are supported, and are recognized by filename suffixes:

File format | Filename suffix ———————— | ————— URDF | “.urdf” SDFormat | “.sdf” MJCF (Mujoco XML) | “.xml” Drake Model Directives | “.dmd.yaml” Wavefront OBJ | “.obj”

The output of parsing is one or more model instances added to the MultibodyPlant provided to the parser at construction.

For an introductory tutorial about parsing, see the <a href=”https://deepnote.com/workspace/Drake-0b3b2c53-a7ad-441b-80f8-bf8350752305/project/Tutorials-2b4fc509-aef2-417d-a40d-6071dfed9199/notebook/authoring_multibody_simulation-3c9697070d3541ee82c0bfe4054ada2d”>Authoring a Multibody Simulation</a> page.

SDFormat files may contain multiple <model> elements. New model instances will be added to plant for each <model> tag in the file.

Note

Adding multiple root-level models, i.e, <model>`s directly under `<sdf>, is deprecated. If you need multiple models in a single file, please use an SDFormat world tag.

URDF files contain a single <robot> element. Only a single model instance will be added to plant.

MJCF (MuJoCo XML) files typically contain many bodies, they will all be added as a single model instance in the plant.

Drake Model Directives are only available via AddModels or AddModelsFromString. The single-model methods (AddModelFromFile, AddModelFromString) cannot load model directives.

OBJ files will infer a model with a single body from the geometry. The OBJ file must contain a single object (in the OBJ-file sense). The body’s mass properties are computed based on uniform distribution of material in the enclosed volume of the mesh (with the approximate density of water: 1000 kg/m³). If the mesh is not a closed manifold, this can produce unexpected results. The spatial inertia of the body is measured at the body frame’s origin. The body’s frame is coincident and fixed with the frame the mesh’s vertices are measured and expressed in. The mesh’s vertices are assumed to be measured in units of meters.

The name of the model and body are determined according to the following prioritized protocol:

  • The non-empty model_name, if given (e.g., in

AddModelFromFile()). - If the object is named in the obj file, that object name is used. - Otherwise, the base name of the file name is used (i.e., the file name with the prefixed directory and extension removed).

If the underlying plant is registered with a SceneGraph instance, the mesh will also be used for all three roles: illustration, perception, and proximity.

Warning

AddModelsFromString() cannot be passed OBJ file contents yet.

For more documentation of Drake-specific treatment of these input formats, see multibody_parsing.

When parsing literal quantities, Parser assumes SI units and radians in the absence of units specified by the format itself. This includes the literals in the explicitly specified files as well as referenced files such as OBJ or other data file formats.

MultibodyPlant requires that model instances have unique names. To support loading multiple instances of the same model file(s) into a plant, Parser offers a few different strategies.

Parser has constructors that take a model name prefix, which gets applied to all models loaded with that Parser instance. The resulting workflow makes multiple parsers to build models for a single plant:

Click to expand C++ code...
Parser left_parser(plant, "left");
 Parser right_parser(plant, "right");
 left_parser.AddModels(arm_model);  // "left::arm"
 right_parser.AddModels(arm_model);  // "right::arm"
 left_parser.AddModels(gripper_model);  // "left::gripper"
 right_parser.AddModels(gripper_model);  // "right::gripper"

For situations where it is convenient to load a model many times, Parser offers optional auto-renaming. When auto-renaming is enabled, name collisions will be resolved by adding a subscript to the name.

Click to expand C++ code...
Parser parser(plant);
 parser.SetAutoRenaming(true);
 // Subscripts are compact, and start at 1.
 parser.AddModels(rock);  // "rock"
 parser.AddModels(rock);  // "rock_1"
 parser.AddModels(rock);  // "rock_2"
 // Subscripts of different base names are independent.
 parser.AddModels(stone);  // "stone"
 parser.AddModels(stone);  // "stone_1"
 parser.AddModels(stone);  // "stone_2"

(Advanced) In the rare case where the user is parsing into a MultibodyPlant and SceneGraph but has created them one at a time instead of using the more convenient AddMultibodyPlant() or AddMultibodyPlantSceneGraph() functions, the Parser constructors accept an optional SceneGraph pointer to specify which SceneGraph to parse into. If it is provided and non-null and the MultibodyPlant is not registered as a source, the Parser will perform the SceneGraph registration into the given plant. We describe this option only for completeness; we strongly discourage anyone from taking advantage of this feature.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.parsing.Parser, plant: drake::multibody::MultibodyPlant<double>, scene_graph: pydrake.geometry.SceneGraph = None, model_name_prefix: str = ‘’) -> None

Creates a Parser that adds models to the given plant and scene_graph. The resulting parser will apply model_name_prefix to the names of any models parsed.

Parameter plant:

A pointer to a mutable MultibodyPlant object to which parsed model(s) will be added; plant->is_finalized() must remain False for as long as the plant is in use by this.

Parameter scene_graph:

A pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr.

Parameter model_name_prefix:

A string that will be added as a scoped name prefix to the names of any models loaded by this parser; when empty, no scoping will be added.

  1. __init__(self: pydrake.multibody.parsing.Parser, plant: drake::multibody::MultibodyPlant<double>, model_name_prefix: str) -> None

Creates a Parser that adds models to the given plant and scene_graph. The resulting parser will apply model_name_prefix to the names of any models parsed.

Parameter plant:

A pointer to a mutable MultibodyPlant object to which parsed model(s) will be added; plant->is_finalized() must remain False for as long as the plant is in use by this.

Parameter model_name_prefix:

A string that will be added as a scoped name prefix to the names of any models loaded by this parser; when empty, no scoping will be added.

AddModels(*args, **kwargs)

Overloaded function.

  1. AddModels(self: pydrake.multibody.parsing.Parser, file_name: str) -> List[drake::TypeSafeIndex<drake::multibody::ModelInstanceTag>]

Parses the input file named in file_name and adds all of its model(s) to plant.

Parameter file_name:

The name of the file to be parsed. The file type will be inferred from the extension.

Returns

The set of model instance indices for the newly added models, including nested models.

Raises

RuntimeError in case of errors.

  1. AddModels(self: pydrake.multibody.parsing.Parser, *, url: str) -> List[drake::TypeSafeIndex<drake::multibody::ModelInstanceTag>]

Parses the input file named in url and adds all of its model(s) to plant. The allowed URL schemes are either file:// for local files or package:// (or model://) to use this Parser’s package_map().

Parameter url:

The file to be parsed. The file type will be inferred from the extension.

Returns

The set of model instance indices for the newly added models, including nested models.

Raises

RuntimeError in case of errors.

  1. AddModels(self: pydrake.multibody.parsing.Parser, *, file_contents: str, file_type: str) -> List[drake::TypeSafeIndex<drake::multibody::ModelInstanceTag>]

Provides same functionality as AddModels, but instead parses the model description text data via file_contents with format dictated by file_type.

Parameter file_contents:

The model data to be parsed.

Parameter file_type:

The data format; must be one of the filename suffixes listed above, without the leading dot (.).

Returns

The set of model instance indices for the newly added models, including nested models.

Raises

RuntimeError in case of errors.

AddModelsFromString(self: pydrake.multibody.parsing.Parser, file_contents: str, file_type: str) List[drake::TypeSafeIndex<drake::multibody::ModelInstanceTag>]

Provides same functionality as AddModels, but instead parses the model description text data via file_contents with format dictated by file_type.

Parameter file_contents:

The model data to be parsed.

Parameter file_type:

The data format; must be one of the filename suffixes listed above, without the leading dot (.).

Returns

The set of model instance indices for the newly added models, including nested models.

Raises

RuntimeError in case of errors.

AddModelsFromUrl(self: pydrake.multibody.parsing.Parser, url: str) List[drake::TypeSafeIndex<drake::multibody::ModelInstanceTag>]

Parses the input file named in url and adds all of its model(s) to plant. The allowed URL schemes are either file:// for local files or package:// (or model://) to use this Parser’s package_map().

Parameter url:

The file to be parsed. The file type will be inferred from the extension.

Returns

The set of model instance indices for the newly added models, including nested models.

Raises

RuntimeError in case of errors.

GetAutoRenaming(self: pydrake.multibody.parsing.Parser) bool

Get the current state of auto-renaming.

See also

the Parser class documentation for more detail.

package_map(self: pydrake.multibody.parsing.Parser) pydrake.multibody.parsing.PackageMap

Gets a mutable reference to the PackageMap used by this parser.

plant(self: pydrake.multibody.parsing.Parser) drake::multibody::MultibodyPlant<double>

Gets a mutable reference to the plant that will be modified by this parser.

SetAutoRenaming(self: pydrake.multibody.parsing.Parser, value: bool) None

Enable or disable auto-renaming. It is disabled by default.

See also

the Parser class documentation for more detail.

SetStrictParsing(self: pydrake.multibody.parsing.Parser) None

Cause all subsequent Add*Model*() operations to use strict parsing; warnings will be treated as errors.

pydrake.multibody.parsing.ProcessModelDirectives(*args, **kwargs)

Overloaded function.

  1. ProcessModelDirectives(directives: pydrake.multibody.parsing.ModelDirectives, parser: pydrake.multibody.parsing.Parser) -> List[pydrake.multibody.parsing.ModelInstanceInfo]

Parses the given model directives using the given parser. The MultibodyPlant (and optionally SceneGraph) being modified are implicitly associated with the Parser object. Returns the list of added models.

  1. ProcessModelDirectives(directives: pydrake.multibody.parsing.ModelDirectives, plant: drake::multibody::MultibodyPlant<double>, parser: pydrake.multibody.parsing.Parser = None) -> List[pydrake.multibody.parsing.ModelInstanceInfo]

Processes model directives for a given MultibodyPlant.