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::Box > | parseBox (const tinyxml2::XMLElement *xml_element) |
Parse a xml box element. More... | |
std::shared_ptr< tesseract_scene_graph::JointCalibration > | parseCalibration (const tinyxml2::XMLElement *xml_element) |
Parse a xml calibration element. More... | |
std::shared_ptr< tesseract_geometry::Capsule > | parseCapsule (const tinyxml2::XMLElement *xml_element) |
Parse a xml capsule element. More... | |
std::shared_ptr< tesseract_scene_graph::Collision > | parseCollision (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool make_convex_meshes) |
Parse xml element collision. More... | |
std::shared_ptr< tesseract_geometry::Cone > | parseCone (const tinyxml2::XMLElement *xml_element) |
Parse a xml cone element. More... | |
std::shared_ptr< tesseract_geometry::Cylinder > | parseCylinder (const tinyxml2::XMLElement *xml_element) |
Parse a xml cylinder element. More... | |
std::shared_ptr< tesseract_scene_graph::JointDynamics > | parseDynamics (const tinyxml2::XMLElement *xml_element) |
Parse a xml dynamics element. More... | |
std::shared_ptr< tesseract_geometry::Geometry > | parseGeometry (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::Inertial > | parseInertial (const tinyxml2::XMLElement *xml_element) |
Parse xml element inertial. More... | |
std::shared_ptr< tesseract_scene_graph::Joint > | parseJoint (const tinyxml2::XMLElement *xml_element) |
Parse xml element joint. More... | |
std::shared_ptr< tesseract_scene_graph::JointLimits > | parseLimits (const tinyxml2::XMLElement *xml_element) |
Parse xml element limits. More... | |
std::shared_ptr< tesseract_scene_graph::Link > | 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. 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::Material > | 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. 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::JointMimic > | parseMimic (const tinyxml2::XMLElement *xml_element) |
Parse xml element mimic. More... | |
std::shared_ptr< tesseract_geometry::Octree > | parseOctomap (const tinyxml2::XMLElement *xml_element, const tesseract_common::ResourceLocator &locator, bool visual) |
Parse xml element octomap. More... | |
std::shared_ptr< tesseract_geometry::Octree > | parseOctree (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::Octree > | parsePointCloud (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::JointSafety > | parseSafetyController (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::Sphere > | parseSphere (const tinyxml2::XMLElement *xml_element) |
Parse a xml sphere element. More... | |
std::unique_ptr< tesseract_scene_graph::SceneGraph > | parseURDFFile (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::SceneGraph > | parseURDFString (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::Visual > | 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. 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" |
std::string tesseract_urdf::makeURDFFilePath | ( | const std::string & | package_path, |
const std::string & | filename | ||
) |
std::string tesseract_urdf::noLeadingSlash | ( | const std::string & | filename | ) |
std::string tesseract_urdf::noTrailingSlash | ( | const std::string & | path | ) |
tesseract_geometry::Box::Ptr tesseract_urdf::parseBox | ( | const tinyxml2::XMLElement * | xml_element | ) |
tesseract_scene_graph::JointCalibration::Ptr tesseract_urdf::parseCalibration | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse a xml calibration element.
xml_element | The xml element |
Definition at line 41 of file calibration.cpp.
tesseract_geometry::Capsule::Ptr tesseract_urdf::parseCapsule | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse a xml capsule element.
xml_element | The xml element |
Definition at line 40 of file capsule.cpp.
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.
xml_element | The xml element |
locator | The Tesseract resource locator |
make_convex_meshes | Flag to indicate if the meshes should be converted to convex hulls |
Definition at line 45 of file collision.cpp.
tesseract_geometry::Cone::Ptr tesseract_urdf::parseCone | ( | const tinyxml2::XMLElement * | xml_element | ) |
tesseract_geometry::Cylinder::Ptr tesseract_urdf::parseCylinder | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse a xml cylinder element.
xml_element | The xml element |
Definition at line 40 of file cylinder.cpp.
tesseract_scene_graph::JointDynamics::Ptr tesseract_urdf::parseDynamics | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse a xml dynamics element.
xml_element | The xml element |
Definition at line 41 of file dynamics.cpp.
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.
xml_element | The xml element |
locator | The Tesseract resource locator |
visual | Indicate if visual |
make_convex_meshes | Flag to indicate if the meshes should be converted to convex hulls |
Definition at line 51 of file geometry.cpp.
tesseract_scene_graph::Inertial::Ptr tesseract_urdf::parseInertial | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse xml element inertial.
xml_element | The xml element |
version | The version number |
Definition at line 41 of file inertial.cpp.
tesseract_scene_graph::Joint::Ptr tesseract_urdf::parseJoint | ( | const tinyxml2::XMLElement * | xml_element | ) |
tesseract_scene_graph::JointLimits::Ptr tesseract_urdf::parseLimits | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse xml element limits.
xml_element | The xml element |
version | The version number |
Definition at line 41 of file limits.cpp.
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.
xml_element | The xml element |
locator | The Tesseract resource locator |
available_materials | The current available materials |
make_convex_meshes | Flag to indicate if the meshes should be converted to convex hulls |
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 | ||
) |
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.
xml_element | The xml element |
available_materials | The current available materials |
allow_anonymous | Indicate if anonymouse materials are allowed |
version | The version number |
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.
std::vector< tesseract_geometry::PolygonMesh::Ptr > tesseract_urdf::parseMesh | ( | const tinyxml2::XMLElement * | xml_element, |
const tesseract_common::ResourceLocator & | locator, | ||
bool | visual, | ||
bool | make_convex | ||
) |
tesseract_scene_graph::JointMimic::Ptr tesseract_urdf::parseMimic | ( | const tinyxml2::XMLElement * | xml_element | ) |
tesseract_geometry::Octree::Ptr tesseract_urdf::parseOctomap | ( | const tinyxml2::XMLElement * | xml_element, |
const tesseract_common::ResourceLocator & | locator, | ||
bool | visual | ||
) |
Parse xml element octomap.
xml_element | The xml element |
locator | The Tesseract resource locator |
visual | Indicate if visual |
version | The version number |
Definition at line 47 of file octomap.cpp.
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.
xml_element | The xml element |
locator | The Tesseract resource locator |
shape_type | The collision/visual shape type to use |
prune | Indicate if the octree should be pruned |
Definition at line 45 of file octree.cpp.
Eigen::Isometry3d tesseract_urdf::parseOrigin | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse xml element origin.
xml_element | The xml element |
version | The version number |
Definition at line 42 of file origin.cpp.
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.
xml_element | The xml element |
locator | The Tesseract locator |
shape_type | The collision/visual geometry to use |
prune | Indicate if the octree should be pruned |
version | The version number |
Definition at line 45 of file point_cloud.cpp.
tesseract_scene_graph::JointSafety::Ptr tesseract_urdf::parseSafetyController | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse xml element safety_controller.
xml_element | The xml element |
version | The version number |
Definition at line 41 of file safety_controller.cpp.
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.
xml_element | The xml element |
locator | The Tesseract resource locator |
visual | Indicate if visual |
version | The version number |
Definition at line 46 of file sdf_mesh.cpp.
tesseract_geometry::Sphere::Ptr tesseract_urdf::parseSphere | ( | const tinyxml2::XMLElement * | xml_element | ) |
Parse a xml sphere element.
xml_element | The xml element |
Definition at line 40 of file sphere.cpp.
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.
URDF | file path |
The | resource locator function |
std::nested_exception | Thrown if error occurs during parsing. Use printNestedException to print contents of the nested exception. |
Definition at line 197 of file urdf_parser.cpp.
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.
urdf_xml_string | URDF xml string |
locator | The resource locator function |
std::nested_exception | Thrown if error occurs during parsing. Use printNestedException to print contents of the nested exception. |
Definition at line 53 of file urdf_parser.cpp.
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.
xml_element | The xml element |
locator | The Tesseract resource locator |
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.
std::string tesseract_urdf::toString | ( | const double & | float_value, |
int | precision = 3 |
||
) |
std::string tesseract_urdf::trailingSlash | ( | const std::string & | path | ) |
tinyxml2::XMLElement * tesseract_urdf::writeBox | ( | const std::shared_ptr< const tesseract_geometry::Box > & | box, |
tinyxml2::XMLDocument & | doc | ||
) |
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.
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.
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
collision | Collision object to be written |
doc | XML 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_name | Name of link to which collision object is attached |
id | If set, this ID will be appended to the geometry name for saving to distinguish between multiple collision geometries on the same link. |
Definition at line 90 of file collision.cpp.
tinyxml2::XMLElement * tesseract_urdf::writeCone | ( | const std::shared_ptr< const tesseract_geometry::Cone > & | cone, |
tinyxml2::XMLDocument & | doc | ||
) |
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.
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.
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
geometry | Geometry to be written |
doc | XML 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. |
filename | The 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") |
Definition at line 196 of file geometry.cpp.
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.
tinyxml2::XMLElement * tesseract_urdf::writeJoint | ( | const std::shared_ptr< const tesseract_scene_graph::Joint > & | joint, |
tinyxml2::XMLDocument & | doc | ||
) |
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.
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
link | Link object to be written |
doc | XML 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. |
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.
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
mesh | Mesh to be saved out and described in XML |
doc | XML 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. |
filename | Desired file location. If package_path is set, this should be relative to the package, If not, this should be an absolute path |
void tesseract_urdf::writeMeshToFile | ( | const std::shared_ptr< const tesseract_geometry::PolygonMesh > & | mesh, |
const std::string & | filepath | ||
) |
tinyxml2::XMLElement * tesseract_urdf::writeMimic | ( | const std::shared_ptr< const tesseract_scene_graph::JointMimic > & | mimic, |
tinyxml2::XMLDocument & | doc | ||
) |
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
octree | Octomap to be written to XML |
doc | XML 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. |
filename | Desired file location. If package_path is set, this should be relative to the package. Otherwise, this should be an absolute path. |
Definition at line 101 of file octomap.cpp.
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
octree | The geometry element containing octree data |
doc | The 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. |
filename | Desired filename relative to the working directory ("octree.ot" or "collision/octree.ot") |
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.
tinyxml2::XMLElement * tesseract_urdf::writeOrigin | ( | const Eigen::Isometry3d & | origin, |
tinyxml2::XMLDocument & | doc | ||
) |
Definition at line 129 of file origin.cpp.
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.
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
sdf_mesh | Mesh to be written |
doc | XML 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. |
filename | Desired file location. If package_path is set, this should be relative to the package. Otherwise, this should be an absolute path |
Definition at line 96 of file sdf_mesh.cpp.
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.
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.
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
visual | Visual object to be written |
doc | XML 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_name | Name of link to which collision object is attached |
id | If set, this ID will be appended to the geometry name for distinguishing between multiple geometries on the same link. |
Definition at line 110 of file visual.cpp.
|
staticconstexpr |
|
staticconstexpr |
Definition at line 45 of file calibration.h.
|
staticconstexpr |
|
staticconstexpr |
Definition at line 46 of file collision.h.
|
staticconstexpr |
|
staticconstexpr |
Definition at line 45 of file cylinder.h.
|
staticconstexpr |
Definition at line 45 of file dynamics.h.
|
staticconstexpr |
Definition at line 46 of file geometry.h.
|
staticconstexpr |
Definition at line 45 of file inertial.h.
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
Definition at line 46 of file material.h.
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
Definition at line 46 of file point_cloud.h.
|
staticconstexpr |
Definition at line 45 of file safety_controller.h.
|
staticconstexpr |
Definition at line 46 of file sdf_mesh.h.
|
staticconstexpr |