Classes | |
struct | AddCollisionFilterGroup |
Directive to add a collision filter group. More... | |
struct | AddDirectives |
Directive to incorporate another model directives file, optionally with its elements prefixed with a namespace. More... | |
struct | AddFrame |
Directive to add a Frame to the scene. More... | |
struct | AddModel |
Directive to add a model from a URDF or SDFormat file to a scene, using a given name for the added instance. More... | |
struct | AddModelInstance |
Directive to add an empty, named model instance to a scene. More... | |
struct | AddWeld |
Directive to add a weld between two named frames, a parent and a child. More... | |
struct | ModelDirective |
Union structure for model directives. More... | |
struct | ModelDirectives |
Top-level structure for a model directives yaml file schema. More... | |
struct | ModelInstanceInfo |
Convenience structure to hold all of the information to add a model instance from a file. More... | |
Functions | |
ModelDirectives | LoadModelDirectives (const std::string &filename) |
ModelDirectives | LoadModelDirectivesFromString (const std::string &model_directives) |
std::string | ResolveModelDirectiveUri (const std::string &uri, const drake::multibody::PackageMap &package_map) |
Converts URIs into filesystem absolute paths. More... | |
void | FlattenModelDirectives (const ModelDirectives &directives, const drake::multibody::PackageMap &package_map, ModelDirectives *out) |
Flatten model directives into a single object. More... | |
std::vector< ModelInstanceInfo > | ProcessModelDirectives (const ModelDirectives &directives, drake::multibody::Parser *parser) |
Parses the given model directives using the given parser. More... | |
void | ProcessModelDirectives (const ModelDirectives &directives, drake::multibody::MultibodyPlant< double > *plant, std::vector< ModelInstanceInfo > *added_models=nullptr, drake::multibody::Parser *parser=nullptr) |
Processes model directives for a given MultibodyPlant. More... | |
const drake::multibody::Frame< double > * | GetScopedFrameByNameMaybe (const drake::multibody::MultibodyPlant< double > &plant, const std::string &full_name) |
Finds an optionally model-scoped frame. More... | |
const drake::multibody::Frame< double > & | GetScopedFrameByName (const drake::multibody::MultibodyPlant< double > &plant, const std::string &full_name) |
Equivalent to GetScopedFrameByNameMaybe , but throws if the frame is not found. More... | |
void drake::multibody::parsing::FlattenModelDirectives | ( | const ModelDirectives & | directives, |
const drake::multibody::PackageMap & | package_map, | ||
ModelDirectives * | out | ||
) |
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.
const drake::multibody::Frame<double>& drake::multibody::parsing::GetScopedFrameByName | ( | const drake::multibody::MultibodyPlant< double > & | plant, |
const std::string & | full_name | ||
) |
Equivalent to GetScopedFrameByNameMaybe
, but throws if the frame is not found.
const drake::multibody::Frame<double>* drake::multibody::parsing::GetScopedFrameByNameMaybe | ( | const drake::multibody::MultibodyPlant< double > & | plant, |
const std::string & | full_name | ||
) |
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)
.
ModelDirectives drake::multibody::parsing::LoadModelDirectives | ( | const std::string & | filename | ) |
ModelDirectives drake::multibody::parsing::LoadModelDirectivesFromString | ( | const std::string & | model_directives | ) |
std::vector<ModelInstanceInfo> drake::multibody::parsing::ProcessModelDirectives | ( | const ModelDirectives & | directives, |
drake::multibody::Parser * | parser | ||
) |
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.
void drake::multibody::parsing::ProcessModelDirectives | ( | const ModelDirectives & | directives, |
drake::multibody::MultibodyPlant< double > * | plant, | ||
std::vector< ModelInstanceInfo > * | added_models = nullptr , |
||
drake::multibody::Parser * | parser = nullptr |
||
) |
Processes model directives for a given MultibodyPlant.
std::string drake::multibody::parsing::ResolveModelDirectiveUri | ( | const std::string & | uri, |
const drake::multibody::PackageMap & | package_map | ||
) |
Converts URIs into filesystem absolute paths.
ModelDirectives refer to their resources by URIs like package://somepackage/somepath/somefile.sdf
, where somepackage refers to the ROS-style package.xml system.