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::CollisionMarginData > | 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. 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, LinkGroups > | 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. 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... | |
Main namespace.
| using tesseract_srdf::ChainGroup = typedef std::vector<std::pair<std::string, std::string> > |
Definition at line 54 of file kinematics_information.h.
| using tesseract_srdf::ChainGroups = typedef std::unordered_map<std::string, ChainGroup> |
Definition at line 55 of file kinematics_information.h.
| using tesseract_srdf::GroupJointStates = typedef std::unordered_map<std::string, GroupsJointStates> |
Definition at line 51 of file kinematics_information.h.
| using tesseract_srdf::GroupNames = typedef std::set<std::string> |
Definition at line 60 of file kinematics_information.h.
| using tesseract_srdf::GroupsJointState = typedef std::unordered_map<std::string, double> |
Definition at line 49 of file kinematics_information.h.
| using tesseract_srdf::GroupsJointStates = typedef std::unordered_map<std::string, GroupsJointState> |
Definition at line 50 of file kinematics_information.h.
| using tesseract_srdf::GroupsTCPs = typedef tesseract_common::AlignedMap<std::string, Eigen::Isometry3d> |
Definition at line 52 of file kinematics_information.h.
| using tesseract_srdf::GroupTCPs = typedef tesseract_common::AlignedMap<std::string, GroupsTCPs> |
Definition at line 53 of file kinematics_information.h.
| using tesseract_srdf::JointGroup = typedef std::vector<std::string> |
Definition at line 56 of file kinematics_information.h.
| using tesseract_srdf::JointGroups = typedef std::unordered_map<std::string, JointGroup> |
Definition at line 57 of file kinematics_information.h.
| using tesseract_srdf::LinkGroup = typedef std::vector<std::string> |
Definition at line 58 of file kinematics_information.h.
| using tesseract_srdf::LinkGroups = typedef std::unordered_map<std::string, LinkGroup> |
Definition at line 59 of file kinematics_information.h.
| bool tesseract_srdf::compareLinkPairAlphabetically | ( | std::reference_wrapper< const tesseract_common::LinkNamesPair > | pair1, |
| std::reference_wrapper< const tesseract_common::LinkNamesPair > | pair2 | ||
| ) |
| std::vector< std::reference_wrapper< const tesseract_common::LinkNamesPair > > tesseract_srdf::getAlphabeticalACMKeys | ( | const tesseract_common::AllowedCollisionEntries & | allowed_collision_entries | ) |
| 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.
| scene_graph | The scene graph |
| locator | The locator used to process the file name URL |
| xml_element | The xml element to process |
| version | The SRDF version |
Definition at line 65 of file configs.cpp.
| 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.
| scene_graph | The tesseract scene graph |
| srdf_xml | The xml element to parse |
| version | The srdf version number |
Definition at line 41 of file collision_margins.cpp.
| 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'
| locator | The locator used to process the file name URL |
| xml_element | The xml element to process |
| version | The SRDF version |
Definition at line 41 of file configs.cpp.
| 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.
| locator | The locator used to process the file name URL |
| xml_element | The xml element to process |
| version | The SRDF version |
Definition at line 123 of file configs.cpp.
| 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.
| scene_graph | The tesseract scene graph |
| srdf_xml | The xml element to parse |
| version | The srdf version number |
Definition at line 40 of file disabled_collisions.cpp.
| 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.
| scene_graph | The tesseract scene graph |
| srdf_xml | The xml element to parse |
| version | The srdf version number |
Definition at line 40 of file groups.cpp.
| 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.
| scene_graph | The tesseract scene graph |
| srdf_xml | The xml element to parse |
| version | The srdf version number |
Definition at line 38 of file group_states.cpp.
| 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.
| scene_graph | The tesseract scene graph |
| srdf_xml | The xml element to parse |
| version | The srdf version number |
Definition at line 47 of file group_tool_center_points.cpp.
| 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.
| locator | The locator used to process the file name URL |
| xml_element | The xml element to process |
| version | The SRDF version |
Definition at line 98 of file configs.cpp.
| void tesseract_srdf::processSRDFAllowedCollisions | ( | tesseract_scene_graph::SceneGraph & | scene_graph, |
| const SRDFModel & | srdf_model | ||
| ) |