Drake
drake::multibody::parsing Namespace Reference

Namespaces

 detail
 

Classes

class  FrameCache
 Keeps a set of frames and the transforms that relate them, using a root or fixed frame to conjoin them all. More...
 
struct  FramedIsometry3
 An isometric transform along with the frame in which it is defined. More...
 
class  PackageMap
 Maps ROS package names to their full path on the local file system. More...
 
class  SdfJoint
 A representation of a <joint> element in an SDF file. More...
 
class  SdfLink
 A representation of a <link> element in an SDF file. More...
 
class  SdfModel
 This class provides a representation of a <model> element within a given SDF specification. More...
 
class  SdfSpec
 This class provides a representation for an SDF specification. More...
 

Functions

ModelInstanceIndex AddModelFromSdfFile (const std::string &file_name, const std::string &model_name, multibody_plant::MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr)
 Parses a <model> element from the SDF file specified by file_name and adds it to plant. More...
 
ModelInstanceIndex AddModelFromSdfFile (const std::string &file_name, multibody_plant::MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr)
 Alternate version of AddModelFromSdfFile which always uses the "name" element from the model tag for the name of the newly created model instance. More...
 
std::vector< ModelInstanceIndexAddModelsFromSdfFile (const std::string &file_name, multibody_plant::MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr)
 Parses all <model> elements from the SDF file specified by file_name and adds them to plant. More...
 
std::ostream & operator<< (std::ostream &out, const PackageMap &package_map)
 
string GetFullPath (const std::string &file_name)
 Obtains the full path of . More...
 
string ResolveFilename (const std::string &filename, const PackageMap &package_map, const std::string &root_dir)
 Resolves the full path of a file. More...
 
multibody_plant::CoulombFriction< doubledefault_friction ()
 Default value of the Coulomb's law coefficients of friction for when they are not specified in the SDF file. More...
 
std::unique_ptr< SdfSpecParseSdfModelFromFile (const std::string &sdf_path)
 Parses a single <model> from file a file named sdf_path. More...
 

Function Documentation

ModelInstanceIndex AddModelFromSdfFile ( const std::string &  file_name,
const std::string &  model_name,
multibody_plant::MultibodyPlant< double > *  plant,
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

Parses a <model> element from the SDF file specified by file_name and adds it to plant.

The SDF file can only contain a single <model> element. <world> elements (used for instance to specify gravity) are ignored by this method. A new model instance will be added to plant.

Exceptions
std::runtime_errorif the file is not in accordance with the SDF specification containing a message with a list of errors encountered while parsing the file.
std::runtime_errorif there is more than one <model> element or zero of them.
std::exceptionif plant is nullptr or if MultibodyPlant::Finalize() was already called on plant.
Parameters
file_nameThe name of the SDF file to be parsed.
model_nameThe name given to the newly created instance of this model. If empty, the "name" attribute from the model tag will be used.
plantA pointer to a mutable MultibodyPlant object to which the model will be added.
scene_graphA pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr.
Returns
The model instance index for the newly added model.
ModelInstanceIndex AddModelFromSdfFile ( const std::string &  file_name,
multibody_plant::MultibodyPlant< double > *  plant,
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

Alternate version of AddModelFromSdfFile which always uses the "name" element from the model tag for the name of the newly created model instance.

std::vector< ModelInstanceIndex > AddModelsFromSdfFile ( const std::string &  file_name,
multibody_plant::MultibodyPlant< double > *  plant,
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

Parses all <model> elements from the SDF file specified by file_name and adds them to plant.

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

Exceptions
std::runtime_errorif the file is not in accordance with the SDF specification containing a message with a list of errors encountered while parsing the file.
std::runtime_errorif the file contains no models.
std::exceptionif plant is nullptr or if MultibodyPlant::Finalize() was already called on plant.
Parameters
file_nameThe name of the SDF file to be parsed.
plantA pointer to a mutable MultibodyPlant object to which the model will be added.
scene_graphA pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr.
Returns
The set of model instance indices for the newly added models.
multibody_plant::CoulombFriction<double> drake::multibody::parsing::default_friction ( )
inline

Default value of the Coulomb's law coefficients of friction for when they are not specified in the SDF file.

std::string GetFullPath ( const std::string &  file_name)

Obtains the full path of .

If file_name is already a full path (i.e., it starts with a "/"), the path is not modified. If file_name is a relative path, this method converts it into an absolute path based on the current working directory.

Exceptions
std::runtime_errorif the file does not exist or if file_name is empty.
std::ostream& drake::multibody::parsing::operator<< ( std::ostream &  out,
const PackageMap package_map 
)
std::unique_ptr< SdfSpec > ParseSdfModelFromFile ( const std::string &  sdf_path)

Parses a single <model> from file a file named sdf_path.

A new SdfSpec object is created which will contain the single model from the file.

Exceptions
std::runtime_errorif there is more than one <model> element in the file.
std::string ResolveFilename ( const std::string &  filename,
const PackageMap package_map,
const std::string &  root_dir 
)

Resolves the full path of a file.

If filename starts with "package:", the ROS packages specified in package_map are searched. Otherwise, filename is appended to the end of root_dir (if it's not already an absolute path) and checked for existence. If the file does not exist or is not found, a warning is printed to std::cerr and an empty string is returned.

Parameters
[in]filenameThe name of the file to find.
[in]package_mapA map where the keys are ROS package names and the values are the paths to the packages. This is only used if filename starts with "package:".
[in]root_dirThe root directory to look in. This is only used when filename does not start with "package:".
Returns
The file's full path or an empty string if the file is not found or does not exist.