Parses SDF and URDF input files into a MultibodyPlant and (optionally) a SceneGraph.
For documentation of Drake-specific extensions and limitations, see Parsing Models for Multibody Dynamics.
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.
#include <drake/multibody/parsing/parser.h>
Public Member Functions | |
Parser (MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr) | |
Creates a Parser that adds models to the given plant and (optionally) scene_graph. More... | |
MultibodyPlant< double > & | plant () |
Gets a mutable reference to the plant that will be modified by this parser. More... | |
PackageMap & | package_map () |
Gets a mutable reference to the PackageMap used by this parser. More... | |
void | SetStrictParsing () |
Cause all subsequent Add*Model*() operations to use strict parsing; warnings will be treated as errors. More... | |
std::vector< ModelInstanceIndex > | AddAllModelsFromFile (const std::string &file_name) |
Parses the SDF, URDF, or MJCF file named in file_name and adds all of its model(s) to plant . More... | |
ModelInstanceIndex | AddModelFromFile (const std::string &file_name, const std::string &model_name={}) |
Parses the SDFormat, URDF, or MJCF file named in file_name and adds one top-level model to plant . More... | |
ModelInstanceIndex | AddModelFromString (const std::string &file_contents, const std::string &file_type, const std::string &model_name={}) |
Provides same functionality as AddModelFromFile, but instead parses the SDFormat or URDF XML data via file_contents with type dictated by file_type . More... | |
Does not allow copy, move, or assignment | |
Parser (const Parser &)=delete | |
Parser & | operator= (const Parser &)=delete |
Parser (Parser &&)=delete | |
Parser & | operator= (Parser &&)=delete |
Friends | |
class | internal::CompositeParse |
|
explicit |
Creates a Parser that adds models to the given plant and (optionally) scene_graph.
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 . |
scene_graph | A pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr. |
std::vector<ModelInstanceIndex> AddAllModelsFromFile | ( | const std::string & | file_name | ) |
Parses the SDF, URDF, or MJCF file named in file_name
and adds all of its model(s) to plant
.
SDFormat files may contain multiple <model>
elements. New model instances will be added to plant
for each <model>
tag in the file.
<model>
s directly under <sdf>
, is deprecated. If you need multiple models in a single file, please use an SDFormat world file.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
.
file_name | The name of the SDF, URDF, or MJCF file to be parsed. The file type will be inferred from the extension. |
std::exception | in case of errors. |
ModelInstanceIndex AddModelFromFile | ( | const std::string & | file_name, |
const std::string & | model_name = {} |
||
) |
Parses the SDFormat, URDF, or MJCF file named in file_name
and adds one top-level model to plant
.
It is an error to call this using an SDFormat file with more than one root-level <model>
element.
ModelInstanceIndex AddModelFromString | ( | const std::string & | file_contents, |
const std::string & | file_type, | ||
const std::string & | model_name = {} |
||
) |
Provides same functionality as AddModelFromFile, but instead parses the SDFormat or URDF XML data via file_contents
with type dictated by file_type
.
file_contents | The XML data to be parsed. |
file_type | The data format; must be either "sdf", "urdf", or "xml". |
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. |
std::exception | in case of errors. |
PackageMap& package_map | ( | ) |
Gets a mutable reference to the PackageMap used by this parser.
MultibodyPlant<double>& plant | ( | ) |
Gets a mutable reference to the plant that will be modified by this parser.
void SetStrictParsing | ( | ) |
Cause all subsequent Add*Model*() operations to use strict parsing; warnings will be treated as errors.
|
friend |