Drake
drake::parsers Namespace Reference

Namespaces

 sdf
 
 urdf
 

Classes

struct  FloatingJointConstants
 Defines constants used by AddFloatingJoint(). More...
 
class  PackageMap
 Maps ROS package names to their full path on the local file system. More...
 

Typedefs

typedef std::map< std::string, intModelInstanceIdTable
 Defines a data type that maps model names to their instance IDs within the RigidBodyTree. More...
 

Functions

void AddModelInstancesToTable (const drake::parsers::ModelInstanceIdTable &source_table, drake::parsers::ModelInstanceIdTable *dest_table)
 Adds the model instances in source_table to dest_table. More...
 
std::ostream & operator<< (std::ostream &out, const PackageMap &package_map)
 
string GetFullPath (const string &file_name)
 
string ResolveFilename (const std::string &filename, const PackageMap &package_map, const std::string &root_dir)
 Resolves the fully-qualified name of a file. More...
 
int AddFloatingJoint (const FloatingBaseType floating_base_type, const vector< int > &body_indices, const std::shared_ptr< RigidBodyFrame< double >> weld_to_frame, const PoseMap *pose_map, RigidBodyTree< double > *tree)
 
int AddFloatingJoint (multibody::joints::FloatingBaseType floating_base_type, const std::vector< int > &body_indices, const std::shared_ptr< RigidBodyFrame< double >> weld_to_frame, const PoseMap *pose_map, RigidBodyTree< double > *tree)
 Adds a floating joint to each body specified by body_indices that does not already have a parent. More...
 

Typedef Documentation

typedef std::map<std::string, int> ModelInstanceIdTable

Defines a data type that maps model names to their instance IDs within the RigidBodyTree.

The model names are defined in a single URDF or SDF file and are thus guaranteed to be unique within an instance of this data type. The instance IDs are determined by by the RigidBodyTree and are unique among all model instances within the tree. This data type is used to inform applications of the IDs that were assigned to model instances as they were added to a RigidBodyTree while parsing a URDF or SDF description.

The model names within this data type are specified by the URDF and SDF. They are not the same as "model instance names" since multiple instances of the same model may be added to the same RigidBodyTree. Model instance names can be decided by the application based on the information contained within this data type. It is recommended, but not required, that applications separately create mappings from model instance IDs to meaningful model instance names. This is because an instance ID, as an integer, does not convey much information about the model instance.

Function Documentation

int drake::parsers::AddFloatingJoint ( multibody::joints::FloatingBaseType  floating_base_type,
const std::vector< int > &  body_indices,
const std::shared_ptr< RigidBodyFrame< double >>  weld_to_frame,
const PoseMap pose_map,
RigidBodyTree< double > *  tree 
)

Adds a floating joint to each body specified by body_indices that does not already have a parent.

This method is only intended to be called by parsers since parsers add bodies to the RigidBodyTree en masse. The logic in this method is necessary to identify which of the rigid bodies specified by body_indices get floating joints.

When manually adding a model instance to the RigidBodyTree, i.e., directly using the C++ API rather than via a parser, this method should not be necessary since floating joints can be directly added by calling RigidBody::setJoint().

Parameters
[in]floating_base_typeThe floating joint's type.
[in]body_indicesA list of body indexes to check. A floating joint is added to any body in this list that does not have a parent joint.
[in]weld_to_frameThe frame to which the floating joint should attach the parent-less non-world bodies. This parameter may be nullptr, in which case the body is welded to the world with zero offset.
[in]pose_mapA mapping where the key is the body's name and the value is the transform from the frame of the body to the frame of the model to which the body belongs. This parameter will may be nullptr, in which case an identity transform is used.
[out]treeThe RigidBodyTree to which to add the floating joints.
Returns
The number of floating joint added to this rigid body tree.
Exceptions
Astd::runtime_error if the floating_base_type is unrecognized or zero floating joints were added to the model.
int drake::parsers::AddFloatingJoint ( const FloatingBaseType  floating_base_type,
const vector< int > &  body_indices,
const std::shared_ptr< RigidBodyFrame< double >>  weld_to_frame,
const PoseMap pose_map,
RigidBodyTree< double > *  tree 
)
void AddModelInstancesToTable ( const drake::parsers::ModelInstanceIdTable source_table,
drake::parsers::ModelInstanceIdTable dest_table 
)

Adds the model instances in source_table to dest_table.

Throws a std::runtime_error if there is a collision in the model names.

std::string GetFullPath ( const string &  file_name)

Here is the call graph for this function:

Here is the caller graph for this function:

std::ostream& drake::parsers::operator<< ( std::ostream &  out,
const PackageMap package_map 
)

Here is the call graph for this function:

std::string ResolveFilename ( const std::string &  filename,
const PackageMap package_map,
const std::string &  root_dir 
)

Resolves the fully-qualified name 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 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 fully-qualified name or an empty string if the file is not found or does not exist.

Here is the call graph for this function: