Functions | Variables
tesseract_urdf Namespace Reference

Functions

std::string makeURDFFilePath (const std::string &package_path, const std::string &filename)
 
std::string noLeadingSlash (const std::string &filename)
 
std::string noTrailingSlash (const std::string &path)
 
std::shared_ptr< tesseract_geometry::BoxparseBox (const tinyxml2::XMLElement *xml_element)
 Parse a xml box element. More...
 
std::shared_ptr< tesseract_scene_graph::JointCalibrationparseCalibration (const tinyxml2::XMLElement *xml_element)
 Parse a xml calibration element. More...
 
std::shared_ptr< tesseract_geometry::CapsuleparseCapsule (const tinyxml2::XMLElement *xml_element)
 Parse a xml capsule element. More...
 
std::shared_ptr< tesseract_scene_graph::CollisionparseCollision (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool make_convex_meshes)
 Parse xml element collision. More...
 
std::shared_ptr< tesseract_geometry::ConeparseCone (const tinyxml2::XMLElement *xml_element)
 Parse a xml cone element. More...
 
std::shared_ptr< tesseract_geometry::CylinderparseCylinder (const tinyxml2::XMLElement *xml_element)
 Parse a xml cylinder element. More...
 
std::shared_ptr< tesseract_scene_graph::JointDynamicsparseDynamics (const tinyxml2::XMLElement *xml_element)
 Parse a xml dynamics element. More...
 
std::shared_ptr< tesseract_geometry::GeometryparseGeometry (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool visual, bool make_convex_meshes)
 Parse xml element geometry. More...
 
std::shared_ptr< tesseract_scene_graph::InertialparseInertial (const tinyxml2::XMLElement *xml_element)
 Parse xml element inertial. More...
 
std::shared_ptr< tesseract_scene_graph::JointparseJoint (const tinyxml2::XMLElement *xml_element)
 Parse xml element joint. More...
 
std::shared_ptr< tesseract_scene_graph::JointLimitsparseLimits (const tinyxml2::XMLElement *xml_element)
 Parse xml element limits. More...
 
std::shared_ptr< tesseract_scene_graph::LinkparseLink (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool make_convex_meshes, std::unordered_map< std::string, std::shared_ptr< tesseract_scene_graph::Material >> &available_materials)
 Parse xml element link. More...
 
tesseract_scene_graph::Link::Ptr parseLink (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool make_convex_meshes, std::unordered_map< std::string, tesseract_scene_graph::Material::Ptr > &available_materials)
 
std::shared_ptr< tesseract_scene_graph::MaterialparseMaterial (const tinyxml2::XMLElement *xml_element, std::unordered_map< std::string, std::shared_ptr< tesseract_scene_graph::Material >> &available_materials, bool allow_anonymous)
 Parse xml element material. More...
 
tesseract_scene_graph::Material::Ptr parseMaterial (const tinyxml2::XMLElement *xml_element, std::unordered_map< std::string, tesseract_scene_graph::Material::Ptr > &available_materials, bool allow_anonymous)
 
std::vector< std::shared_ptr< tesseract_geometry::PolygonMesh > > parseMesh (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool visual, bool make_convex)
 Parse xml element mesh. More...
 
std::shared_ptr< tesseract_scene_graph::JointMimicparseMimic (const tinyxml2::XMLElement *xml_element)
 Parse xml element mimic. More...
 
std::shared_ptr< tesseract_geometry::OctreeparseOctomap (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool visual)
 Parse xml element octomap. More...
 
std::shared_ptr< tesseract_geometry::OctreeparseOctree (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, tesseract_geometry::OctreeSubType shape_type, bool prune)
 Parse xml element octree. More...
 
Eigen::Isometry3d parseOrigin (const tinyxml2::XMLElement *xml_element)
 Parse xml element origin. More...
 
std::shared_ptr< tesseract_geometry::OctreeparsePointCloud (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, tesseract_geometry::OctreeSubType shape_type, bool prune)
 Parse xml element point_cloud. More...
 
std::shared_ptr< tesseract_scene_graph::JointSafetyparseSafetyController (const tinyxml2::XMLElement *xml_element)
 Parse xml element safety_controller. More...
 
std::vector< std::shared_ptr< tesseract_geometry::SDFMesh > > parseSDFMesh (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool visual)
 Parse xml element sdf_mesh. More...
 
std::shared_ptr< tesseract_geometry::SphereparseSphere (const tinyxml2::XMLElement *xml_element)
 Parse a xml sphere element. More...
 
std::unique_ptr< tesseract_scene_graph::SceneGraphparseURDFFile (const std::string &path, const tesseract_common::ResourceLocator &locator)
 Parse a URDF file into a Tesseract Scene Graph. More...
 
std::unique_ptr< tesseract_scene_graph::SceneGraphparseURDFString (const std::string &urdf_xml_string, const tesseract_common::ResourceLocator &locator)
 Parse a URDF string into a Tesseract Scene Graph. More...
 
std::shared_ptr< tesseract_scene_graph::VisualparseVisual (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, std::unordered_map< std::string, std::shared_ptr< tesseract_scene_graph::Material >> &available_materials)
 Parse xml element visual. More...
 
tesseract_scene_graph::Visual::Ptr parseVisual (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, std::unordered_map< std::string, tesseract_scene_graph::Material::Ptr > &available_materials)
 
std::string toString (const double &float_value, int precision=3)
 
std::string trailingSlash (const std::string &path)
 
tinyxml2::XMLElement * writeBox (const std::shared_ptr< const tesseract_geometry::Box > &box, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeCalibration (const std::shared_ptr< const tesseract_scene_graph::JointCalibration > &calibration, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeCapsule (const std::shared_ptr< const tesseract_geometry::Capsule > &capsule, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeCollision (const std::shared_ptr< const tesseract_scene_graph::Collision > &collision, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &link_name, int id)
 writeCollision Write collision object to URDF XML More...
 
tinyxml2::XMLElement * writeCone (const std::shared_ptr< const tesseract_geometry::Cone > &cone, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeCylinder (const std::shared_ptr< const tesseract_geometry::Cylinder > &cylinder, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeDynamics (const std::shared_ptr< const tesseract_scene_graph::JointDynamics > &dynamics, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeGeometry (const std::shared_ptr< const tesseract_geometry::Geometry > &geometry, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &filename)
 writeGeometry Write geometry to URDF XML More...
 
tinyxml2::XMLElement * writeInertial (const std::shared_ptr< const tesseract_scene_graph::Inertial > &inertial, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeJoint (const std::shared_ptr< const tesseract_scene_graph::Joint > &joint, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeLimits (const std::shared_ptr< const tesseract_scene_graph::JointLimits > &limits, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeLink (const std::shared_ptr< const tesseract_scene_graph::Link > &link, tinyxml2::XMLDocument &doc, const std::string &package_path)
 writeLink Write a link to URDF XML More...
 
tinyxml2::XMLElement * writeMaterial (const std::shared_ptr< const tesseract_scene_graph::Material > &material, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeMesh (const std::shared_ptr< const tesseract_geometry::PolygonMesh > &mesh, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &filename)
 writeMesh Write a mesh to URDF XML and PLY file More...
 
void writeMeshToFile (const std::shared_ptr< const tesseract_geometry::PolygonMesh > &mesh, const std::string &filepath)
 
tinyxml2::XMLElement * writeMimic (const std::shared_ptr< const tesseract_scene_graph::JointMimic > &mimic, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeOctomap (const std::shared_ptr< const tesseract_geometry::Octree > &octree, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &filename)
 writeOctomap Write octomap to URDF XML. This is non-standard URDF / tesseract-exclusive More...
 
tinyxml2::XMLElement * writeOctree (const std::shared_ptr< const tesseract_geometry::Octree > &octree, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &filename)
 writeOctree Write octree out to file, and generate appropriate xml More...
 
tinyxml2::XMLElement * writeOctree (const tesseract_geometry::Octree::ConstPtr &octree, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &filename)
 
tinyxml2::XMLElement * writeOrigin (const Eigen::Isometry3d &origin, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeSafetyController (const std::shared_ptr< const tesseract_scene_graph::JointSafety > &safety, tinyxml2::XMLDocument &doc)
 
tinyxml2::XMLElement * writeSDFMesh (const std::shared_ptr< const tesseract_geometry::SDFMesh > &sdf_mesh, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &filename)
 writeSDFMesh Write SDF Mesh to URDF XML. This is non-standard URDF / tesseract-exclusive More...
 
tinyxml2::XMLElement * writeSphere (const std::shared_ptr< const tesseract_geometry::Sphere > &sphere, tinyxml2::XMLDocument &doc)
 
void writeURDFFile (const std::shared_ptr< const tesseract_scene_graph::SceneGraph > &sg, const std::string &package_path, const std::string &urdf_name="")
 
tinyxml2::XMLElement * writeVisual (const std::shared_ptr< const tesseract_scene_graph::Visual > &visual, tinyxml2::XMLDocument &doc, const std::string &package_path, const std::string &link_name, int id)
 writeVisual Write one visual geometry object to URDF XML More...
 

Variables

static constexpr std::string_view BOX_ELEMENT_NAME = "box"
 
static constexpr std::string_view CALIBRATION_ELEMENT_NAME = "calibration"
 
static constexpr std::string_view CAPSULE_ELEMENT_NAME = "tesseract:capsule"
 
static constexpr std::string_view COLLISION_ELEMENT_NAME = "collision"
 
static constexpr std::string_view CONE_ELEMENT_NAME = "tesseract:cone"
 
static constexpr std::string_view CYLINDER_ELEMENT_NAME = "cylinder"
 
static constexpr std::string_view DYNAMICS_ELEMENT_NAME = "dynamics"
 
static constexpr std::string_view GEOMETRY_ELEMENT_NAME = "geometry"
 
static constexpr std::string_view INERTIAL_ELEMENT_NAME = "inertial"
 
static constexpr std::string_view JOINT_ELEMENT_NAME = "joint"
 
static constexpr std::string_view LIMITS_ELEMENT_NAME = "limit"
 
static constexpr std::string_view LINK_ELEMENT_NAME = "link"
 
static constexpr std::string_view MATERIAL_ELEMENT_NAME = "material"
 
static constexpr std::string_view MESH_ELEMENT_NAME = "mesh"
 
static constexpr std::string_view MIMIC_ELEMENT_NAME = "mimic"
 
static constexpr std::string_view OCTOMAP_ELEMENT_NAME = "tesseract:octomap"
 
static constexpr std::string_view OCTREE_ELEMENT_NAME = "tesseract:octree"
 
static constexpr std::string_view ORIGIN_ELEMENT_NAME = "origin"
 
static constexpr std::string_view POINT_CLOUD_ELEMENT_NAME = "tesseract:point_cloud"
 
static constexpr std::string_view SAFETY_CONTROLLER_ELEMENT_NAME = "safety_controller"
 
static constexpr std::string_view SDF_MESH_ELEMENT_NAME = "tesseract:sdf_mesh"
 
static constexpr std::string_view SPHERE_ELEMENT_NAME = "sphere"
 
static constexpr std::string_view VISUAL_ELEMENT_NAME = "visual"
 

Function Documentation

◆ makeURDFFilePath()

std::string tesseract_urdf::makeURDFFilePath ( const std::string &  package_path,
const std::string &  filename 
)

Definition at line 55 of file utils.cpp.

◆ noLeadingSlash()

std::string tesseract_urdf::noLeadingSlash ( const std::string &  filename)

Definition at line 45 of file utils.cpp.

◆ noTrailingSlash()

std::string tesseract_urdf::noTrailingSlash ( const std::string &  path)

Definition at line 35 of file utils.cpp.

◆ parseBox()

tesseract_geometry::Box::Ptr tesseract_urdf::parseBox ( const tinyxml2::XMLElement *  xml_element)

Parse a xml box element.

Parameters
xml_elementThe xml element
Returns
Tesseract Geometry Box

Definition at line 41 of file box.cpp.

◆ parseCalibration()

tesseract_scene_graph::JointCalibration::Ptr tesseract_urdf::parseCalibration ( const tinyxml2::XMLElement *  xml_element)

Parse a xml calibration element.

Parameters
xml_elementThe xml element
Returns
Tesseract JointCalibration

Definition at line 41 of file calibration.cpp.

◆ parseCapsule()

tesseract_geometry::Capsule::Ptr tesseract_urdf::parseCapsule ( const tinyxml2::XMLElement *  xml_element)

Parse a xml capsule element.

Parameters
xml_elementThe xml element
Returns
Tesseract Geometry Capsule

Definition at line 40 of file capsule.cpp.

◆ parseCollision()

tesseract_scene_graph::Collision::Ptr tesseract_urdf::parseCollision ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  make_convex_meshes 
)

Parse xml element collision.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
make_convex_meshesFlag to indicate if the meshes should be converted to convex hulls
Returns
A Collision object

Definition at line 45 of file collision.cpp.

◆ parseCone()

tesseract_geometry::Cone::Ptr tesseract_urdf::parseCone ( const tinyxml2::XMLElement *  xml_element)

Parse a xml cone element.

Parameters
xml_elementThe xml element
Returns
Tesseract Geometry Cone

Definition at line 40 of file cone.cpp.

◆ parseCylinder()

tesseract_geometry::Cylinder::Ptr tesseract_urdf::parseCylinder ( const tinyxml2::XMLElement *  xml_element)

Parse a xml cylinder element.

Parameters
xml_elementThe xml element
Returns
Tesseract Geometry Cylinder

Definition at line 40 of file cylinder.cpp.

◆ parseDynamics()

tesseract_scene_graph::JointDynamics::Ptr tesseract_urdf::parseDynamics ( const tinyxml2::XMLElement *  xml_element)

Parse a xml dynamics element.

Parameters
xml_elementThe xml element
Returns
Tesseract JointDynamics

Definition at line 41 of file dynamics.cpp.

◆ parseGeometry()

tesseract_geometry::Geometry::Ptr tesseract_urdf::parseGeometry ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  visual,
bool  make_convex_meshes 
)

Parse xml element geometry.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
visualIndicate if visual
make_convex_meshesFlag to indicate if the meshes should be converted to convex hulls
Returns
A Tesseract Geometry

Definition at line 51 of file geometry.cpp.

◆ parseInertial()

tesseract_scene_graph::Inertial::Ptr tesseract_urdf::parseInertial ( const tinyxml2::XMLElement *  xml_element)

Parse xml element inertial.

Parameters
xml_elementThe xml element
versionThe version number
Returns
A Tesseract Inertial

Definition at line 41 of file inertial.cpp.

◆ parseJoint()

tesseract_scene_graph::Joint::Ptr tesseract_urdf::parseJoint ( const tinyxml2::XMLElement *  xml_element)

Parse xml element joint.

Parameters
xml_elementThe xml element
versionThe version number
Returns
A Tesseract Joint

Definition at line 48 of file joint.cpp.

◆ parseLimits()

tesseract_scene_graph::JointLimits::Ptr tesseract_urdf::parseLimits ( const tinyxml2::XMLElement *  xml_element)

Parse xml element limits.

Parameters
xml_elementThe xml element
versionThe version number
Returns
A Tesseract JointLimits

Definition at line 41 of file limits.cpp.

◆ parseLink() [1/2]

std::shared_ptr<tesseract_scene_graph::Link> tesseract_urdf::parseLink ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  make_convex_meshes,
std::unordered_map< std::string, std::shared_ptr< tesseract_scene_graph::Material >> &  available_materials 
)

Parse xml element link.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
available_materialsThe current available materials
make_convex_meshesFlag to indicate if the meshes should be converted to convex hulls
Returns
A Tesseract Link

◆ parseLink() [2/2]

tesseract_scene_graph::Link::Ptr tesseract_urdf::parseLink ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  make_convex_meshes,
std::unordered_map< std::string, tesseract_scene_graph::Material::Ptr > &  available_materials 
)

Definition at line 47 of file link.cpp.

◆ parseMaterial() [1/2]

std::shared_ptr<tesseract_scene_graph::Material> tesseract_urdf::parseMaterial ( const tinyxml2::XMLElement *  xml_element,
std::unordered_map< std::string, std::shared_ptr< tesseract_scene_graph::Material >> &  available_materials,
bool  allow_anonymous 
)

Parse xml element material.

Parameters
xml_elementThe xml element
available_materialsThe current available materials
allow_anonymousIndicate if anonymouse materials are allowed
versionThe version number
Returns
A Tesseract Material

◆ parseMaterial() [2/2]

tesseract_scene_graph::Material::Ptr tesseract_urdf::parseMaterial ( const tinyxml2::XMLElement *  xml_element,
std::unordered_map< std::string, tesseract_scene_graph::Material::Ptr > &  available_materials,
bool  allow_anonymous 
)

Definition at line 45 of file material.cpp.

◆ parseMesh()

std::vector< tesseract_geometry::PolygonMesh::Ptr > tesseract_urdf::parseMesh ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  visual,
bool  make_convex 
)

Parse xml element mesh.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
visualIndicate if visual
make_convexFlag to indicate if the mesh should be converted to a convex hull
Returns
A vector of Tesseract Meshes

Definition at line 47 of file mesh.cpp.

◆ parseMimic()

tesseract_scene_graph::JointMimic::Ptr tesseract_urdf::parseMimic ( const tinyxml2::XMLElement *  xml_element)

Parse xml element mimic.

Parameters
xml_elementThe xml element
versionThe version number
Returns
A Tesseract JointMimic

Definition at line 42 of file mimic.cpp.

◆ parseOctomap()

tesseract_geometry::Octree::Ptr tesseract_urdf::parseOctomap ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  visual 
)

Parse xml element octomap.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
visualIndicate if visual
versionThe version number
Returns
A Tesseract Geometry Octree

Definition at line 47 of file octomap.cpp.

◆ parseOctree()

tesseract_geometry::Octree::Ptr tesseract_urdf::parseOctree ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
tesseract_geometry::OctreeSubType  shape_type,
bool  prune 
)

Parse xml element octree.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
shape_typeThe collision/visual shape type to use
pruneIndicate if the octree should be pruned
Returns
A Tesseract Geometry Octree

Definition at line 45 of file octree.cpp.

◆ parseOrigin()

Eigen::Isometry3d tesseract_urdf::parseOrigin ( const tinyxml2::XMLElement *  xml_element)

Parse xml element origin.

Parameters
xml_elementThe xml element
versionThe version number
Returns
A Eigen::Isometry3d

Definition at line 42 of file origin.cpp.

◆ parsePointCloud()

tesseract_geometry::Octree::Ptr tesseract_urdf::parsePointCloud ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
tesseract_geometry::OctreeSubType  shape_type,
bool  prune 
)

Parse xml element point_cloud.

Parameters
xml_elementThe xml element
locatorThe Tesseract locator
shape_typeThe collision/visual geometry to use
pruneIndicate if the octree should be pruned
versionThe version number
Returns
A Tesseract Geometry Octree

Definition at line 45 of file point_cloud.cpp.

◆ parseSafetyController()

tesseract_scene_graph::JointSafety::Ptr tesseract_urdf::parseSafetyController ( const tinyxml2::XMLElement *  xml_element)

Parse xml element safety_controller.

Parameters
xml_elementThe xml element
versionThe version number
Returns
A Tesseract JointSafety

Definition at line 41 of file safety_controller.cpp.

◆ parseSDFMesh()

std::vector< tesseract_geometry::SDFMesh::Ptr > tesseract_urdf::parseSDFMesh ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
bool  visual 
)

Parse xml element sdf_mesh.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
visualIndicate if visual
versionThe version number
Returns
A vector of Tesseract SDFMeshes

Definition at line 46 of file sdf_mesh.cpp.

◆ parseSphere()

tesseract_geometry::Sphere::Ptr tesseract_urdf::parseSphere ( const tinyxml2::XMLElement *  xml_element)

Parse a xml sphere element.

Parameters
xml_elementThe xml element
Returns
Tesseract Geometry Sphere

Definition at line 40 of file sphere.cpp.

◆ parseURDFFile()

std::unique_ptr< tesseract_scene_graph::SceneGraph > tesseract_urdf::parseURDFFile ( const std::string &  path,
const tesseract_common::ResourceLocator locator 
)

Parse a URDF file into a Tesseract Scene Graph.

Parameters
URDFfile path
Theresource locator function
Exceptions
std::nested_exceptionThrown if error occurs during parsing. Use printNestedException to print contents of the nested exception.
Returns
Tesseract Scene Graph, nullptr if failed to parse URDF

Definition at line 197 of file urdf_parser.cpp.

◆ parseURDFString()

std::unique_ptr< tesseract_scene_graph::SceneGraph > tesseract_urdf::parseURDFString ( const std::string &  urdf_xml_string,
const tesseract_common::ResourceLocator locator 
)

Parse a URDF string into a Tesseract Scene Graph.

Parameters
urdf_xml_stringURDF xml string
locatorThe resource locator function
Exceptions
std::nested_exceptionThrown if error occurs during parsing. Use printNestedException to print contents of the nested exception.
Returns
Tesseract Scene Graph, nullptr if failed to parse URDF

Definition at line 53 of file urdf_parser.cpp.

◆ parseVisual() [1/2]

std::shared_ptr<tesseract_scene_graph::Visual> tesseract_urdf::parseVisual ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
std::unordered_map< std::string, std::shared_ptr< tesseract_scene_graph::Material >> &  available_materials 
)

Parse xml element visual.

Parameters
xml_elementThe xml element
locatorThe Tesseract resource locator
Returns
A Visual object

◆ parseVisual() [2/2]

tesseract_scene_graph::Visual::Ptr tesseract_urdf::parseVisual ( const tinyxml2::XMLElement *  xml_element,
const tesseract_common::ResourceLocator locator,
std::unordered_map< std::string, tesseract_scene_graph::Material::Ptr > &  available_materials 
)

Definition at line 47 of file visual.cpp.

◆ toString()

std::string tesseract_urdf::toString ( const double &  float_value,
int  precision = 3 
)

Definition at line 12 of file utils.cpp.

◆ trailingSlash()

std::string tesseract_urdf::trailingSlash ( const std::string &  path)

Definition at line 20 of file utils.cpp.

◆ writeBox()

tinyxml2::XMLElement * tesseract_urdf::writeBox ( const std::shared_ptr< const tesseract_geometry::Box > &  box,
tinyxml2::XMLDocument &  doc 
)

Definition at line 70 of file box.cpp.

◆ writeCalibration()

tinyxml2::XMLElement * tesseract_urdf::writeCalibration ( const std::shared_ptr< const tesseract_scene_graph::JointCalibration > &  calibration,
tinyxml2::XMLDocument &  doc 
)

Definition at line 66 of file calibration.cpp.

◆ writeCapsule()

tinyxml2::XMLElement * tesseract_urdf::writeCapsule ( const std::shared_ptr< const tesseract_geometry::Capsule > &  capsule,
tinyxml2::XMLDocument &  doc 
)

Definition at line 52 of file capsule.cpp.

◆ writeCollision()

tinyxml2::XMLElement * tesseract_urdf::writeCollision ( const std::shared_ptr< const tesseract_scene_graph::Collision > &  collision,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  link_name,
int  id = -1 
)

writeCollision Write collision object to URDF XML

Parameters
collisionCollision object to be written
docXML Document to which XML will belong
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
link_nameName of link to which collision object is attached
idIf set, this ID will be appended to the geometry name for saving to distinguish between multiple collision geometries on the same link.
Returns
An XML element representing the collision object in URDF format.

Definition at line 90 of file collision.cpp.

◆ writeCone()

tinyxml2::XMLElement * tesseract_urdf::writeCone ( const std::shared_ptr< const tesseract_geometry::Cone > &  cone,
tinyxml2::XMLDocument &  doc 
)

Definition at line 52 of file cone.cpp.

◆ writeCylinder()

tinyxml2::XMLElement * tesseract_urdf::writeCylinder ( const std::shared_ptr< const tesseract_geometry::Cylinder > &  cylinder,
tinyxml2::XMLDocument &  doc 
)

Definition at line 52 of file cylinder.cpp.

◆ writeDynamics()

tinyxml2::XMLElement * tesseract_urdf::writeDynamics ( const std::shared_ptr< const tesseract_scene_graph::JointDynamics > &  dynamics,
tinyxml2::XMLDocument &  doc 
)

Definition at line 66 of file dynamics.cpp.

◆ writeGeometry()

tinyxml2::XMLElement * tesseract_urdf::writeGeometry ( const std::shared_ptr< const tesseract_geometry::Geometry > &  geometry,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  filename 
)

writeGeometry Write geometry to URDF XML

Parameters
geometryGeometry to be written
docXML Document to which xml will belong
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
filenameThe desired filename. The extension will be added according to geometry type. If package_path is set, this should be relative to the package (e.g. "collision/link1_geometry"). If package_path is not set, this should be an absolute path (e.g. "/tmp/link1_geometry")
Returns
xml element representing the geometry in URDF format.

Definition at line 196 of file geometry.cpp.

◆ writeInertial()

tinyxml2::XMLElement * tesseract_urdf::writeInertial ( const std::shared_ptr< const tesseract_scene_graph::Inertial > &  inertial,
tinyxml2::XMLDocument &  doc 
)

Definition at line 89 of file inertial.cpp.

◆ writeJoint()

tinyxml2::XMLElement * tesseract_urdf::writeJoint ( const std::shared_ptr< const tesseract_scene_graph::Joint > &  joint,
tinyxml2::XMLDocument &  doc 
)

Definition at line 233 of file joint.cpp.

◆ writeLimits()

tinyxml2::XMLElement * tesseract_urdf::writeLimits ( const std::shared_ptr< const tesseract_scene_graph::JointLimits > &  limits,
tinyxml2::XMLDocument &  doc 
)

Definition at line 74 of file limits.cpp.

◆ writeLink()

tinyxml2::XMLElement * tesseract_urdf::writeLink ( const std::shared_ptr< const tesseract_scene_graph::Link > &  link,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path 
)

writeLink Write a link to URDF XML

Parameters
linkLink object to be written
docXML Document to which element will belong
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
Returns
XML element representing link in URDF format

Definition at line 111 of file link.cpp.

◆ writeMaterial()

tinyxml2::XMLElement * tesseract_urdf::writeMaterial ( const std::shared_ptr< const tesseract_scene_graph::Material > &  material,
tinyxml2::XMLDocument &  doc 
)

Definition at line 124 of file material.cpp.

◆ writeMesh()

tinyxml2::XMLElement * tesseract_urdf::writeMesh ( const std::shared_ptr< const tesseract_geometry::PolygonMesh > &  mesh,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  filename 
)

writeMesh Write a mesh to URDF XML and PLY file

Parameters
meshMesh to be saved out and described in XML
docXML Document to manage generated XML
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
filenameDesired file location. If package_path is set, this should be relative to the package, If not, this should be an absolute path
Returns
XML element representing the mesh object in URDF format.

Definition at line 131 of file mesh.cpp.

◆ writeMeshToFile()

void tesseract_urdf::writeMeshToFile ( const std::shared_ptr< const tesseract_geometry::PolygonMesh > &  mesh,
const std::string &  filepath 
)

Definition at line 140 of file utils.cpp.

◆ writeMimic()

tinyxml2::XMLElement * tesseract_urdf::writeMimic ( const std::shared_ptr< const tesseract_scene_graph::JointMimic > &  mimic,
tinyxml2::XMLDocument &  doc 
)

Definition at line 66 of file mimic.cpp.

◆ writeOctomap()

tinyxml2::XMLElement * tesseract_urdf::writeOctomap ( const std::shared_ptr< const tesseract_geometry::Octree > &  octree,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  filename 
)

writeOctomap Write octomap to URDF XML. This is non-standard URDF / tesseract-exclusive

Parameters
octreeOctomap to be written to XML
docXML document to manage generated xml
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
filenameDesired file location. If package_path is set, this should be relative to the package. Otherwise, this should be an absolute path.
Returns
XML element representing the octomap object in URDF Format

Definition at line 101 of file octomap.cpp.

◆ writeOctree() [1/2]

tinyxml2::XMLElement* tesseract_urdf::writeOctree ( const std::shared_ptr< const tesseract_geometry::Octree > &  octree,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  filename 
)

writeOctree Write octree out to file, and generate appropriate xml

Parameters
octreeThe geometry element containing octree data
docThe XML document to which to add the xml data
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
filenameDesired filename relative to the working directory ("octree.ot" or "collision/octree.ot")
Returns
An XML element containing information on the saved file.

◆ writeOctree() [2/2]

tinyxml2::XMLElement* tesseract_urdf::writeOctree ( const tesseract_geometry::Octree::ConstPtr octree,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  filename 
)

Definition at line 73 of file octree.cpp.

◆ writeOrigin()

tinyxml2::XMLElement * tesseract_urdf::writeOrigin ( const Eigen::Isometry3d &  origin,
tinyxml2::XMLDocument &  doc 
)

Definition at line 129 of file origin.cpp.

◆ writeSafetyController()

tinyxml2::XMLElement * tesseract_urdf::writeSafetyController ( const std::shared_ptr< const tesseract_scene_graph::JointSafety > &  safety,
tinyxml2::XMLDocument &  doc 
)

Definition at line 76 of file safety_controller.cpp.

◆ writeSDFMesh()

tinyxml2::XMLElement * tesseract_urdf::writeSDFMesh ( const std::shared_ptr< const tesseract_geometry::SDFMesh > &  sdf_mesh,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  filename 
)

writeSDFMesh Write SDF Mesh to URDF XML. This is non-standard URDF / tesseract-exclusive

Parameters
sdf_meshMesh to be written
docXML Document to manage generated XML
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
filenameDesired file location. If package_path is set, this should be relative to the package. Otherwise, this should be an absolute path
Returns
XML element representing the sdf mesh object in URDF format

Definition at line 96 of file sdf_mesh.cpp.

◆ writeSphere()

tinyxml2::XMLElement * tesseract_urdf::writeSphere ( const std::shared_ptr< const tesseract_geometry::Sphere > &  sphere,
tinyxml2::XMLDocument &  doc 
)

Definition at line 49 of file sphere.cpp.

◆ writeURDFFile()

void tesseract_urdf::writeURDFFile ( const std::shared_ptr< const tesseract_scene_graph::SceneGraph > &  sg,
const std::string &  package_path,
const std::string &  urdf_name = "" 
)

Definition at line 218 of file urdf_parser.cpp.

◆ writeVisual()

tinyxml2::XMLElement * tesseract_urdf::writeVisual ( const std::shared_ptr< const tesseract_scene_graph::Visual > &  visual,
tinyxml2::XMLDocument &  doc,
const std::string &  package_path,
const std::string &  link_name,
int  id = -1 
)

writeVisual Write one visual geometry object to URDF XML

Parameters
visualVisual object to be written
docXML Document to which XML will belong
package_path/<path>/<to>/<your-package>. If set, geometry will be saved relative to the package. If not set, geometry will be saved with absolute paths.
link_nameName of link to which collision object is attached
idIf set, this ID will be appended to the geometry name for distinguishing between multiple geometries on the same link.
Returns
An XML element representing the collision object in URDF format.

Definition at line 110 of file visual.cpp.

Variable Documentation

◆ BOX_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::BOX_ELEMENT_NAME = "box"
staticconstexpr

Definition at line 45 of file box.h.

◆ CALIBRATION_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::CALIBRATION_ELEMENT_NAME = "calibration"
staticconstexpr

Definition at line 45 of file calibration.h.

◆ CAPSULE_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::CAPSULE_ELEMENT_NAME = "tesseract:capsule"
staticconstexpr

Definition at line 45 of file capsule.h.

◆ COLLISION_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::COLLISION_ELEMENT_NAME = "collision"
staticconstexpr

Definition at line 46 of file collision.h.

◆ CONE_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::CONE_ELEMENT_NAME = "tesseract:cone"
staticconstexpr

Definition at line 45 of file cone.h.

◆ CYLINDER_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::CYLINDER_ELEMENT_NAME = "cylinder"
staticconstexpr

Definition at line 45 of file cylinder.h.

◆ DYNAMICS_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::DYNAMICS_ELEMENT_NAME = "dynamics"
staticconstexpr

Definition at line 45 of file dynamics.h.

◆ GEOMETRY_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::GEOMETRY_ELEMENT_NAME = "geometry"
staticconstexpr

Definition at line 46 of file geometry.h.

◆ INERTIAL_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::INERTIAL_ELEMENT_NAME = "inertial"
staticconstexpr

Definition at line 45 of file inertial.h.

◆ JOINT_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::JOINT_ELEMENT_NAME = "joint"
staticconstexpr

Definition at line 45 of file joint.h.

◆ LIMITS_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::LIMITS_ELEMENT_NAME = "limit"
staticconstexpr

Definition at line 45 of file limits.h.

◆ LINK_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::LINK_ELEMENT_NAME = "link"
staticconstexpr

Definition at line 47 of file link.h.

◆ MATERIAL_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::MATERIAL_ELEMENT_NAME = "material"
staticconstexpr

Definition at line 46 of file material.h.

◆ MESH_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::MESH_ELEMENT_NAME = "mesh"
staticconstexpr

Definition at line 47 of file mesh.h.

◆ MIMIC_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::MIMIC_ELEMENT_NAME = "mimic"
staticconstexpr

Definition at line 45 of file mimic.h.

◆ OCTOMAP_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::OCTOMAP_ELEMENT_NAME = "tesseract:octomap"
staticconstexpr

Definition at line 46 of file octomap.h.

◆ OCTREE_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::OCTREE_ELEMENT_NAME = "tesseract:octree"
staticconstexpr

Definition at line 46 of file octree.h.

◆ ORIGIN_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::ORIGIN_ELEMENT_NAME = "origin"
staticconstexpr

Definition at line 43 of file origin.h.

◆ POINT_CLOUD_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::POINT_CLOUD_ELEMENT_NAME = "tesseract:point_cloud"
staticconstexpr

Definition at line 46 of file point_cloud.h.

◆ SAFETY_CONTROLLER_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::SAFETY_CONTROLLER_ELEMENT_NAME = "safety_controller"
staticconstexpr

Definition at line 45 of file safety_controller.h.

◆ SDF_MESH_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::SDF_MESH_ELEMENT_NAME = "tesseract:sdf_mesh"
staticconstexpr

Definition at line 46 of file sdf_mesh.h.

◆ SPHERE_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::SPHERE_ELEMENT_NAME = "sphere"
staticconstexpr

Definition at line 45 of file sphere.h.

◆ VISUAL_ELEMENT_NAME

constexpr std::string_view tesseract_urdf::VISUAL_ELEMENT_NAME = "visual"
staticconstexpr

Definition at line 47 of file visual.h.



tesseract_urdf
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:07