FancySafeBot 0.0.1
A safe robotics library
Loading...
Searching...
No Matches
Urdf Parsing

Parsing URDF files to get rigid body tree object. More...

Classes

class  fsb::urdf::UrdfError
 Urdf parsing error. More...
 
class  fsb::urdf::NameMap
 Name map relating names to object indices. More...
 
class  fsb::urdf::UrdfNameMap
 Name-index map of joints and bodies in rigid body tree. More...
 
struct  fsb::urdf::UrdfJoint
 Structure representing a URDF joint. More...
 

Enumerations

enum class  fsb::urdf::UrdfErrorType {
  UrdfErrorType::SUCCESS , UrdfErrorType::VALUE_CONVERSION_FAILED , UrdfErrorType::RANGE_ERROR , UrdfErrorType::LOAD_FILE_ERROR ,
  UrdfErrorType::PARSE_ERROR , UrdfErrorType::MISSING_ROBOT , UrdfErrorType::MISSING_NAME , UrdfErrorType::REPEATED_NAME ,
  UrdfErrorType::MISSING_JOINT_TYPE , UrdfErrorType::INVALID_JOINT_TYPE , UrdfErrorType::JOINT_INVALID_AXIS , UrdfErrorType::MISSING_JOINT_PARENT ,
  UrdfErrorType::MISSING_PARENT_LINK_ATTRIBUTE , UrdfErrorType::MISSING_JOINT_CHILD , UrdfErrorType::MISSING_CHILD_LINK_ATTRIBUTE , UrdfErrorType::MISSING_BODY_INERTIAL ,
  UrdfErrorType::MISSING_BODY_MASS , UrdfErrorType::MISSING_BODY_INERTIA , UrdfErrorType::MISSING_INERTIA_ATTRIBUTE , UrdfErrorType::MISSING_MASS_VALUE_ATTRIBUTE ,
  UrdfErrorType::BODY_PRINCIPAL_INERTIA , UrdfErrorType::BODY_INERTIA_NOT_POSITIVE_DEFINITE , UrdfErrorType::MAX_JOINTS_EXCEEDED , UrdfErrorType::MAX_BODIES_EXCEEDED ,
  UrdfErrorType::MAX_COORDINATES_EXCEEDED , UrdfErrorType::MAX_DOFS_EXCEEDED , UrdfErrorType::BODY_TREE_ERROR , UrdfErrorType::JOINT_PARENT_BODY_NOT_FOUND ,
  UrdfErrorType::JOINT_CHILD_BODY_NOT_FOUND
}
 Errors from parsing URDF. More...
 
enum class  fsb::urdf::NameMapError { NameMapError::SUCCESS , NameMapError::NOT_FOUND , NameMapError::EXISTS }
 Name map errors. More...
 

Functions

size_t fsb::urdf::string_to_index (const std::string &str, UrdfError &err)
 Parse a string to extract an unsigned integer as index value.
 
real_t fsb::urdf::string_to_real (const std::string &str, UrdfError &err)
 Parse a string to extract a real value.
 
std::vector< std::string > fsb::urdf::split_string_spaces (const std::string &str)
 Split a string with space character as delimiter.
 
Vec3 fsb::urdf::string_to_vector (const std::string &str, UrdfError &err)
 Converts a string to a vector with 3 elements separated by the space character.
 
Quaternion fsb::urdf::string_to_quaternion (const std::string &str, UrdfError &err)
 Converts a string to a quaternion.
 
UrdfJoint fsb::urdf::urdf_parse_joint (const std::string &fname, const tinyxml2::XMLElement *joint_xml, UrdfError &err)
 Parse a URDF joint element.
 
Transform fsb::urdf::urdf_parse_origin (const std::string &fname, const std::string &el_name, const tinyxml2::XMLElement *el_xml, UrdfError &err)
 Parse first child origin element to get coordinate transform.
 
MotionVector fsb::urdf::urdf_parse_origin_offset (const std::string &fname, const std::string &body_name, const tinyxml2::XMLElement *body_xml, UrdfError &err)
 Parse first child origin offset element.
 
Inertia fsb::urdf::urdf_parse_inertia_mass (const std::string &fname, const std::string &body_name, const tinyxml2::XMLElement *inertial_xml, real_t &body_mass, UrdfError &err)
 Parse inertial element from URDF file.
 
BodyTree fsb::urdf::parse_urdf_string (const std::string &urdf_string, UrdfNameMap &name_map, UrdfError &err)
 Parse URDF file string to get body tree object.
 
BodyTree fsb::urdf::parse_urdf_file (const std::string &urdf_filename, UrdfNameMap &name_map, UrdfError &err)
 Parse URDF file to get body tree object.
 

Detailed Description

Parsing URDF files to get rigid body tree object.

Enumeration Type Documentation

◆ NameMapError

enum class fsb::urdf::NameMapError
strong

Name map errors.

Enumerator
SUCCESS 

No error.

NOT_FOUND 

Joint or body name not found.

EXISTS 

Joint or body already exists.

◆ UrdfErrorType

enum class fsb::urdf::UrdfErrorType
strong

Errors from parsing URDF.

Enumerator
SUCCESS 

No error.

VALUE_CONVERSION_FAILED 

Failed to convert to numerical value.

RANGE_ERROR 

Value out of range.

LOAD_FILE_ERROR 

File failed to load.

PARSE_ERROR 

Failed to parse URDF XML.

MISSING_ROBOT 

Missing robot element.

MISSING_NAME 

Missing name attribute.

REPEATED_NAME 

Repeated element name.

MISSING_JOINT_TYPE 

Missing joint type attribute.

INVALID_JOINT_TYPE 

Invalid joint type attribute.

JOINT_INVALID_AXIS 

Invalid joint axis.

MISSING_JOINT_PARENT 

Joint parent not found.

MISSING_PARENT_LINK_ATTRIBUTE 

Missing parent attribute on joint element.

MISSING_JOINT_CHILD 

Missing child attribute on joint element.

MISSING_CHILD_LINK_ATTRIBUTE 

Missing child attribute on joint element.

MISSING_BODY_INERTIAL 

Missing inertial element for body.

MISSING_BODY_MASS 

Missing mass element.

MISSING_BODY_INERTIA 

Missing inertia element.

MISSING_INERTIA_ATTRIBUTE 

Missing inertia attribute ixx, iyy, or izz.

MISSING_MASS_VALUE_ATTRIBUTE 

Missing mass value attribute.

BODY_PRINCIPAL_INERTIA 

Failed to determine inertia principal axis.

BODY_INERTIA_NOT_POSITIVE_DEFINITE 

Inertia is not positive definite.

MAX_JOINTS_EXCEEDED 

Maximum number of joints exceeded.

MAX_BODIES_EXCEEDED 

Maximum number of bodies exceeded.

MAX_COORDINATES_EXCEEDED 

Maximum number of position coordinates exceeded.

MAX_DOFS_EXCEEDED 

Maximum number of degrees of freedom exceeded.

BODY_TREE_ERROR 

Failed to add body to tree.

JOINT_PARENT_BODY_NOT_FOUND 

Joint parent body not found.

JOINT_CHILD_BODY_NOT_FOUND 

Joint child body not found.

Function Documentation

◆ parse_urdf_file()

BodyTree fsb::urdf::parse_urdf_file ( const std::string &  urdf_filename,
UrdfNameMap name_map,
UrdfError err 
)

Parse URDF file to get body tree object.

Parameters
urdf_filenameInput URDF filename
name_mapOutput name map for rigid body tree
errError object
Returns
Body tree parsed from URDF

◆ parse_urdf_string()

BodyTree fsb::urdf::parse_urdf_string ( const std::string &  urdf_string,
UrdfNameMap name_map,
UrdfError err 
)

Parse URDF file string to get body tree object.

Parameters
urdf_stringString of URDF contents
name_mapOutput name map for rigid body tree
errError object
Returns
Body tree parsed from URDF

◆ split_string_spaces()

std::vector< std::string > fsb::urdf::split_string_spaces ( const std::string &  str)

Split a string with space character as delimiter.

Parameters
strString to split
Returns
Array of strings between space characters.

◆ string_to_index()

size_t fsb::urdf::string_to_index ( const std::string &  str,
UrdfError err 
)

Parse a string to extract an unsigned integer as index value.

The standard function std::strtol is used to parse the string and ignores trailing string characters after parsing the value.

Parameters
strString to convert to an index value (unsigned integer)
errError from parsing
Returns
Index value

◆ string_to_quaternion()

Quaternion fsb::urdf::string_to_quaternion ( const std::string &  str,
UrdfError err 
)

Converts a string to a quaternion.

Parameters
strString to convert to a quaternion
errError from parsing string.
Returns
Quaternion from string

◆ string_to_real()

real_t fsb::urdf::string_to_real ( const std::string &  str,
UrdfError err 
)

Parse a string to extract a real value.

The standard function std::strtod is used to parse the string and ignores trailing string characters after parsing the value.

Parameters
strString to convert to a real value
errError from parsing
Returns
Real value

◆ string_to_vector()

Vec3 fsb::urdf::string_to_vector ( const std::string &  str,
UrdfError err 
)

Converts a string to a vector with 3 elements separated by the space character.

Parameters
strConvert string to 3-element vector
errError from parsing string.
Returns
Vector from string

◆ urdf_parse_inertia_mass()

Inertia fsb::urdf::urdf_parse_inertia_mass ( const std::string &  fname,
const std::string &  body_name,
const tinyxml2::XMLElement *  inertial_xml,
real_t &  body_mass,
UrdfError err 
)

Parse inertial element from URDF file.

This function parses the inertial element of a body in a URDF file. An example xml element is:

<inertial>
<mass value="1.0"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
</inertial>
Parameters
[in]fnameFile name of the URDF file
[in]body_nameBody name to which the inertial element belongs
[in]inertial_xmlPointer to the inertial XML element
[out]body_massMass of the body
[out]errError object to store any parsing errors
Returns
Inertia tensor

◆ urdf_parse_joint()

UrdfJoint fsb::urdf::urdf_parse_joint ( const std::string &  fname,
const tinyxml2::XMLElement *  joint_xml,
UrdfError err 
)

Parse a URDF joint element.

An example xml snippet with a joint element is shown below.

<joint name="jointname" type="revolute">
<parent link="parent_linkname"/>
<child link="child_linkname"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
</joint>
Parameters
[in]fnameName of the file being parsed
[in]joint_xmlXML element representing the joint
[out]errError status returned after parsing
Returns
Parsed URDF joint

◆ urdf_parse_origin()

Transform fsb::urdf::urdf_parse_origin ( const std::string &  fname,
const std::string &  el_name,
const tinyxml2::XMLElement *  el_xml,
UrdfError err 
)

Parse first child origin element to get coordinate transform.

Here is an example xml snippet with the child origin of an element

<element name="elname">
<origin xyz="0 0 0" rpy="0 0 0" />
</element>
Parameters
fnameName of file being parsed
el_nameParent element name containing origin
el_xmlParent element containing origin
errError status returned after parsing
Returns
Coordinate transform of origin

◆ urdf_parse_origin_offset()

MotionVector fsb::urdf::urdf_parse_origin_offset ( const std::string &  fname,
const std::string &  body_name,
const tinyxml2::XMLElement *  body_xml,
UrdfError err 
)

Parse first child origin offset element.

The origin offset is a custom element for the Fancy Safe Bot library and is prefixed fsb:. An XML snippet shows an example offset below. The angular offset is an axis-angle representation of a rotation in radians.

<element name="elname">
<fsb:origin_offset xyz="0 0 0" rotvec="0 0 0" />
</element>
Parameters
fnameName of file being parsed
body_nameParent body element name containing origin offset
body_xmlParent element containing origin offset
errError status returned after parsing
Returns
Linear and angular coordinate transform offset