group_tool_center_points.h
Go to the documentation of this file.
1 
27 #ifndef TESSERACT_SRDF_TOOL_CENTER_POINTS_H
28 #define TESSERACT_SRDF_TOOL_CENTER_POINTS_H
29 
32 #include <array>
34 
37 
38 namespace tinyxml2
39 {
40 class XMLElement; // NOLINT
41 }
42 
43 namespace tesseract_srdf
44 {
53  const tinyxml2::XMLElement* srdf_xml,
54  const std::array<int, 3>& version);
55 
56 } // namespace tesseract_srdf
57 
58 #endif // TESSERACT_SRDF_TOOL_CENTER_POINTS_H
tesseract_srdf::parseGroupTCPs
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.
Definition: group_tool_center_points.cpp:47
tesseract_srdf
Main namespace.
Definition: collision_margins.h:43
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::SceneGraph
tesseract_srdf::GroupTCPs
tesseract_common::AlignedMap< std::string, GroupsTCPs > GroupTCPs
Definition: kinematics_information.h:53
kinematics_information.h
This hold the kinematics information.
fwd.h
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tinyxml2
macros.h


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