Classes | Typedefs | Functions
tesseract_srdf Namespace Reference

Main namespace. More...

Classes

struct  KinematicsInformation
 This hold the kinematics information used to create the SRDF and is the data container for the manipulator manager. More...
 
class  SRDFModel
 Representation of semantic information about the robot. More...
 

Typedefs

using ChainGroup = std::vector< std::pair< std::string, std::string > >
 
using ChainGroups = std::unordered_map< std::string, ChainGroup >
 
using GroupJointStates = std::unordered_map< std::string, GroupsJointStates >
 
using GroupNames = std::set< std::string >
 
using GroupsJointState = std::unordered_map< std::string, double >
 
using GroupsJointStates = std::unordered_map< std::string, GroupsJointState >
 
using GroupsTCPs = tesseract_common::AlignedMap< std::string, Eigen::Isometry3d >
 
using GroupTCPs = tesseract_common::AlignedMap< std::string, GroupsTCPs >
 
using JointGroup = std::vector< std::string >
 
using JointGroups = std::unordered_map< std::string, JointGroup >
 
using LinkGroup = std::vector< std::string >
 
using LinkGroups = std::unordered_map< std::string, LinkGroup >
 

Functions

bool compareLinkPairAlphabetically (std::reference_wrapper< const tesseract_common::LinkNamesPair > pair1, std::reference_wrapper< const tesseract_common::LinkNamesPair > pair2)
 Used to sort a pair of strings alphabetically - first by the pair.first and then by pair.second. More...
 
std::vector< std::reference_wrapper< const tesseract_common::LinkNamesPair > > getAlphabeticalACMKeys (const tesseract_common::AllowedCollisionEntries &allowed_collision_entries)
 Returns an alphabetically sorted vector of ACM keys (the link pairs) More...
 
tesseract_common::CalibrationInfo parseCalibrationConfig (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_common::ResourceLocator &locator, const tinyxml2::XMLElement *xml_element, const std::array< int, 3 > &version)
 Parse calibration config xml element. More...
 
std::shared_ptr< tesseract_common::CollisionMarginDataparseCollisionMargins (const tesseract_scene_graph::SceneGraph &scene_graph, const tinyxml2::XMLElement *srdf_xml, const std::array< int, 3 > &version)
 Parse allowed collisions from srdf xml element. More...
 
std::filesystem::path parseConfigFilePath (const tesseract_common::ResourceLocator &locator, const tinyxml2::XMLElement *xml_element, const std::array< int, 3 > &version)
 Parse a config xml element. More...
 
tesseract_common::ContactManagersPluginInfo parseContactManagersPluginConfig (const tesseract_common::ResourceLocator &locator, const tinyxml2::XMLElement *xml_element, const std::array< int, 3 > &version)
 Parse contact managers plugin config xml element. More...
 
tesseract_common::AllowedCollisionMatrix parseDisabledCollisions (const tesseract_scene_graph::SceneGraph &scene_graph, const tinyxml2::XMLElement *srdf_xml, const std::array< int, 3 > &version)
 Parse allowed collisions from srdf xml element. More...
 
std::tuple< GroupNames, ChainGroups, JointGroups, LinkGroupsparseGroups (const tesseract_scene_graph::SceneGraph &scene_graph, const tinyxml2::XMLElement *srdf_xml, const std::array< int, 3 > &version)
 Parse groups from srdf xml element. More...
 
GroupJointStates parseGroupStates (const tesseract_scene_graph::SceneGraph &scene_graph, const GroupNames &group_names, const tinyxml2::XMLElement *srdf_xml, const std::array< int, 3 > &version)
 Parse groups states from srdf xml element. More...
 
GroupTCPs parseGroupTCPs (const tesseract_scene_graph::SceneGraph &scene_graph, const tinyxml2::XMLElement *srdf_xml, const std::array< int, 3 > &version)
 Parse groups tool center points from srdf xml element. More...
 
tesseract_common::KinematicsPluginInfo parseKinematicsPluginConfig (const tesseract_common::ResourceLocator &locator, const tinyxml2::XMLElement *xml_element, const std::array< int, 3 > &version)
 Parse kinematics plugin config xml element. More...
 
void processSRDFAllowedCollisions (tesseract_scene_graph::SceneGraph &scene_graph, const SRDFModel &srdf_model)
 Add allowed collisions to the scene graph. More...
 

Detailed Description

Main namespace.

Typedef Documentation

◆ ChainGroup

using tesseract_srdf::ChainGroup = typedef std::vector<std::pair<std::string, std::string> >

Definition at line 54 of file kinematics_information.h.

◆ ChainGroups

using tesseract_srdf::ChainGroups = typedef std::unordered_map<std::string, ChainGroup>

Definition at line 55 of file kinematics_information.h.

◆ GroupJointStates

using tesseract_srdf::GroupJointStates = typedef std::unordered_map<std::string, GroupsJointStates>

Definition at line 51 of file kinematics_information.h.

◆ GroupNames

using tesseract_srdf::GroupNames = typedef std::set<std::string>

Definition at line 60 of file kinematics_information.h.

◆ GroupsJointState

using tesseract_srdf::GroupsJointState = typedef std::unordered_map<std::string, double>

Definition at line 49 of file kinematics_information.h.

◆ GroupsJointStates

using tesseract_srdf::GroupsJointStates = typedef std::unordered_map<std::string, GroupsJointState>

Definition at line 50 of file kinematics_information.h.

◆ GroupsTCPs

using tesseract_srdf::GroupsTCPs = typedef tesseract_common::AlignedMap<std::string, Eigen::Isometry3d>

Definition at line 52 of file kinematics_information.h.

◆ GroupTCPs

Definition at line 53 of file kinematics_information.h.

◆ JointGroup

using tesseract_srdf::JointGroup = typedef std::vector<std::string>

Definition at line 56 of file kinematics_information.h.

◆ JointGroups

using tesseract_srdf::JointGroups = typedef std::unordered_map<std::string, JointGroup>

Definition at line 57 of file kinematics_information.h.

◆ LinkGroup

using tesseract_srdf::LinkGroup = typedef std::vector<std::string>

Definition at line 58 of file kinematics_information.h.

◆ LinkGroups

using tesseract_srdf::LinkGroups = typedef std::unordered_map<std::string, LinkGroup>

Definition at line 59 of file kinematics_information.h.

Function Documentation

◆ compareLinkPairAlphabetically()

bool tesseract_srdf::compareLinkPairAlphabetically ( std::reference_wrapper< const tesseract_common::LinkNamesPair pair1,
std::reference_wrapper< const tesseract_common::LinkNamesPair pair2 
)

Used to sort a pair of strings alphabetically - first by the pair.first and then by pair.second.

Parameters
pair1First pair of strings
pair2Second pair of strings
Returns
True if pair1 should go before pair2 (is closer to A)

Definition at line 39 of file utils.cpp.

◆ getAlphabeticalACMKeys()

std::vector< std::reference_wrapper< const tesseract_common::LinkNamesPair > > tesseract_srdf::getAlphabeticalACMKeys ( const tesseract_common::AllowedCollisionEntries allowed_collision_entries)

Returns an alphabetically sorted vector of ACM keys (the link pairs)

Parameters
allowed_collision_entriesEntries to be sorted
Returns
An alphabetically sorted vector of ACM keys (the link pairs)

Definition at line 53 of file utils.cpp.

◆ parseCalibrationConfig()

tesseract_common::CalibrationInfo tesseract_srdf::parseCalibrationConfig ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_common::ResourceLocator locator,
const tinyxml2::XMLElement *  xml_element,
const std::array< int, 3 > &  version 
)

Parse calibration config xml element.

Parameters
scene_graphThe scene graph
locatorThe locator used to process the file name URL
xml_elementThe xml element to process
versionThe SRDF version
Returns
The calibration information

Definition at line 65 of file configs.cpp.

◆ parseCollisionMargins()

tesseract_common::CollisionMarginData::Ptr tesseract_srdf::parseCollisionMargins ( const tesseract_scene_graph::SceneGraph scene_graph,
const tinyxml2::XMLElement *  srdf_xml,
const std::array< int, 3 > &  version 
)

Parse allowed collisions from srdf xml element.

Parameters
scene_graphThe tesseract scene graph
srdf_xmlThe xml element to parse
versionThe srdf version number
Returns
Allowed Collision Matrix

Definition at line 41 of file collision_margins.cpp.

◆ parseConfigFilePath()

std::filesystem::path tesseract_srdf::parseConfigFilePath ( const tesseract_common::ResourceLocator locator,
const tinyxml2::XMLElement *  xml_element,
const std::array< int, 3 > &  version 
)

Parse a config xml element.

It expects the element to have the attribute 'filename'

Parameters
locatorThe locator used to process the file name URL
xml_elementThe xml element to process
versionThe SRDF version
Returns
The extracted file path

Definition at line 41 of file configs.cpp.

◆ parseContactManagersPluginConfig()

tesseract_common::ContactManagersPluginInfo tesseract_srdf::parseContactManagersPluginConfig ( const tesseract_common::ResourceLocator locator,
const tinyxml2::XMLElement *  xml_element,
const std::array< int, 3 > &  version 
)

Parse contact managers plugin config xml element.

Parameters
locatorThe locator used to process the file name URL
xml_elementThe xml element to process
versionThe SRDF version
Returns
The contact managers plugin information

Definition at line 123 of file configs.cpp.

◆ parseDisabledCollisions()

tesseract_common::AllowedCollisionMatrix tesseract_srdf::parseDisabledCollisions ( const tesseract_scene_graph::SceneGraph scene_graph,
const tinyxml2::XMLElement *  srdf_xml,
const std::array< int, 3 > &  version 
)

Parse allowed collisions from srdf xml element.

Parameters
scene_graphThe tesseract scene graph
srdf_xmlThe xml element to parse
versionThe srdf version number
Returns
Allowed Collision Matrix

Definition at line 40 of file disabled_collisions.cpp.

◆ parseGroups()

std::tuple< GroupNames, ChainGroups, JointGroups, LinkGroups > tesseract_srdf::parseGroups ( const tesseract_scene_graph::SceneGraph scene_graph,
const tinyxml2::XMLElement *  srdf_xml,
const std::array< int, 3 > &  version 
)

Parse groups from srdf xml element.

Parameters
scene_graphThe tesseract scene graph
srdf_xmlThe xml element to parse
versionThe srdf version number
Returns
GroupNames, ChainGroups, JointGroups, LinkGroups

Definition at line 40 of file groups.cpp.

◆ parseGroupStates()

GroupJointStates tesseract_srdf::parseGroupStates ( const tesseract_scene_graph::SceneGraph scene_graph,
const GroupNames group_names,
const tinyxml2::XMLElement *  srdf_xml,
const std::array< int, 3 > &  version 
)

Parse groups states from srdf xml element.

Parameters
scene_graphThe tesseract scene graph
srdf_xmlThe xml element to parse
versionThe srdf version number
Returns
Group states

Definition at line 38 of file group_states.cpp.

◆ parseGroupTCPs()

GroupTCPs tesseract_srdf::parseGroupTCPs ( const tesseract_scene_graph::SceneGraph scene_graph,
const tinyxml2::XMLElement *  srdf_xml,
const std::array< int, 3 > &  version 
)

Parse groups tool center points from srdf xml element.

Parameters
scene_graphThe tesseract scene graph
srdf_xmlThe xml element to parse
versionThe srdf version number
Returns
Group Tool Center Points

Definition at line 47 of file group_tool_center_points.cpp.

◆ parseKinematicsPluginConfig()

tesseract_common::KinematicsPluginInfo tesseract_srdf::parseKinematicsPluginConfig ( const tesseract_common::ResourceLocator locator,
const tinyxml2::XMLElement *  xml_element,
const std::array< int, 3 > &  version 
)

Parse kinematics plugin config xml element.

Parameters
locatorThe locator used to process the file name URL
xml_elementThe xml element to process
versionThe SRDF version
Returns
The kinematics plugin information

Definition at line 98 of file configs.cpp.

◆ processSRDFAllowedCollisions()

void tesseract_srdf::processSRDFAllowedCollisions ( tesseract_scene_graph::SceneGraph scene_graph,
const SRDFModel srdf_model 
)

Add allowed collisions to the scene graph.

Parameters
scene_graphThe scene graph to add allowed collisions data
srdf_modelThe srdf model to extract allowed collisions

Definition at line 33 of file utils.cpp.



tesseract_srdf
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:04