pydrake.multibody.parsing

SDF and URDF parsing for MultibodyPlant and SceneGraph.

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.

Add(self: pydrake.multibody.parsing.PackageMap, arg0: str, arg1: str) → None

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

Contains(self: pydrake.multibody.parsing.PackageMap, arg0: str) → bool

Returns true if and only if this PackageMap contains package_name.

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

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

PopulateFromEnvironment(self: pydrake.multibody.parsing.PackageMap, arg0: 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.

PopulateFromFolder(self: pydrake.multibody.parsing.PackageMap, arg0: 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.

PopulateUpstreamToDrake(self: pydrake.multibody.parsing.PackageMap, arg0: str) → None

Crawls up the directory tree from model_file to drake searching for package.xml files. Adds the packages described by these package.xml files. If model_file is not in drake, this method returns without doing anything.

Parameter model_file:
The model file whose directory is the start of the search for package.xml files. This file must be an SDF or URDF file.
__init__(self: pydrake.multibody.parsing.PackageMap) → None

A constructor that initializes an empty map.

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

Returns the number of entries in this PackageMap.

class pydrake.multibody.parsing.Parser

Parses SDF and URDF input files into a MultibodyPlant and (optionally) a SceneGraph.

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

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

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

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

Parameter file_name:
The name of the SDF or URDF 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.
Raises:RuntimeError in case of errors.
AddModelFromFile(self: pydrake.multibody.parsing.Parser, file_name: str, model_name: str = '') → drake::TypeSafeIndex<drake::multibody::ModelInstanceTag>

Parses the SDF or URDF file named in file_name and adds one model to plant. It is an error to call this using an SDF file with more than one <model> element.

Parameter file_name:
The name of the SDF or URDF file to be parsed. The file type will be inferred from the extension.
Parameter model_name:
The name given to the newly created instance of this model. If empty, the “name” attribute from the <model> or <robot> tag will be used.
Returns:The instance index for the newly added model.
Raises:RuntimeError in case of errors.
__init__(self: pydrake.multibody.parsing.Parser, plant: drake::multibody::MultibodyPlant<double>, scene_graph: drake::geometry::SceneGraph<double> = None) → None

Creates a Parser that adds models to the given plant and (optionally) scene_graph.

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 used 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.
package_map(self: pydrake.multibody.parsing.Parser) → pydrake.multibody.parsing.PackageMap

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