Classes | |
| struct | adjacency_detector |
| struct | children_detector |
| class | Collision |
| struct | cycle_detector |
| class | Inertial |
| class | Joint |
| class | JointCalibration |
| class | JointDynamics |
| class | JointLimits |
| class | JointMimic |
| class | JointSafety |
| Parameters for Joint Safety Controllers. More... | |
| struct | kdl_sub_tree_builder |
| Every time a vertex is visited for the first time add a new segment to the KDL Tree;. More... | |
| struct | kdl_tree_builder |
| Every time a vertex is visited for the first time add a new segment to the KDL Tree;. More... | |
| struct | KDLTreeData |
| The KDLTreeData populated when parsing scene graph. More... | |
| class | Link |
| class | Material |
| class | SceneGraph |
| struct | SceneState |
| This holds a state of the scene. More... | |
| struct | ShortestPath |
| Holds the shortest path information. More... | |
| struct | tree_detector |
| struct | ugraph_vertex_copier |
| class | Visual |
Typedefs | |
| using | EdgeProperty = boost::property< boost::edge_joint_t, std::shared_ptr< Joint >, boost::property< boost::edge_weight_t, double > > |
| EdgeProperty. More... | |
| using | Graph = boost::adjacency_list< boost::listS, boost::listS, boost::bidirectionalS, VertexProperty, EdgeProperty, GraphProperty > |
| using | GraphProperty = boost::property< boost::graph_name_t, std::string, boost::property< boost::graph_root_t, std::string > > |
| Defines the boost graph property. More... | |
| using | UGraph = boost::adjacency_list< boost::listS, boost::listS, boost::undirectedS, VertexProperty, EdgeProperty, GraphProperty > |
| using | VertexProperty = boost::property< boost::vertex_link_t, std::shared_ptr< Link >, boost::property< boost::vertex_link_visible_t, bool, boost::property< boost::vertex_link_collision_enabled_t, bool > >> |
| Defines the boost graph vertex property. More... | |
Enumerations | |
| enum | JointType : std::uint8_t { JointType::UNKNOWN, JointType::REVOLUTE, JointType::CONTINUOUS, JointType::PRISMATIC, JointType::FLOATING, JointType::PLANAR, JointType::FIXED } |
Functions | |
| KDL::Frame | convert (const Eigen::Isometry3d &transform) |
| Convert Eigen::Isometry3d to KDL::Frame. More... | |
| KDL::Jacobian | convert (const Eigen::MatrixXd &jacobian) |
| Convert Eigen::Matrix to KDL::Jacobian. More... | |
| KDL::Vector | convert (const Eigen::Vector3d &vector) |
| Convert Eigen::Vector3d to KDL::Vector. More... | |
| Eigen::Isometry3d | convert (const KDL::Frame &frame) |
| Convert KDL::Frame to Eigen::Isometry3d. More... | |
| Eigen::MatrixXd | convert (const KDL::Jacobian &jacobian) |
| Convert KDL::Jacobian to Eigen::Matrix. More... | |
| Eigen::MatrixXd | convert (const KDL::Jacobian &jacobian, const std::vector< int > &q_nrs) |
| Convert a subset of KDL::Jacobian to Eigen::Matrix. More... | |
| Eigen::Vector3d | convert (const KDL::Vector &vector) |
| Convert KDL::Vector to Eigen::Vector3d. More... | |
| KDL::RigidBodyInertia | convert (const std::shared_ptr< const Inertial > &inertial) |
| Convert Tesseract Inertail to KDL Inertial. More... | |
| KDL::Joint | convert (const std::shared_ptr< const Joint > &joint) |
| Convert Tesseract Joint to KDL Joint. More... | |
| std::ostream & | operator<< (std::ostream &os, const JointCalibration &calibration) |
| std::ostream & | operator<< (std::ostream &os, const JointDynamics &dynamics) |
| std::ostream & | operator<< (std::ostream &os, const JointLimits &limits) |
| std::ostream & | operator<< (std::ostream &os, const JointMimic &mimic) |
| std::ostream & | operator<< (std::ostream &os, const JointSafety &safety) |
| std::ostream & | operator<< (std::ostream &os, const JointType &type) |
| std::ostream & | operator<< (std::ostream &os, const ShortestPath &path) |
| KDLTreeData | parseSceneGraph (const SceneGraph &scene_graph) |
| Convert a Tesseract SceneGraph into a KDL Tree. More... | |
| KDLTreeData | parseSceneGraph (const SceneGraph &scene_graph, const std::vector< std::string > &joint_names, const std::unordered_map< std::string, double > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) |
| Convert a portion of a Tesseract SceneGraph into a KDL Tree. More... | |
| using tesseract_scene_graph::EdgeProperty = typedef boost::property<boost::edge_joint_t, std::shared_ptr<Joint>, boost::property<boost::edge_weight_t, double> > |
| using tesseract_scene_graph::Graph = typedef boost:: adjacency_list<boost::listS, boost::listS, boost::bidirectionalS, VertexProperty, EdgeProperty, GraphProperty> |
| using tesseract_scene_graph::GraphProperty = typedef boost::property<boost::graph_name_t, std::string, boost::property<boost::graph_root_t, std::string> > |
| using tesseract_scene_graph::UGraph = typedef boost::adjacency_list<boost::listS, boost::listS, boost::undirectedS, VertexProperty, EdgeProperty, GraphProperty> |
| using tesseract_scene_graph::VertexProperty = typedef boost::property< boost::vertex_link_t, std::shared_ptr<Link>, boost::property<boost::vertex_link_visible_t, bool, boost::property<boost::vertex_link_collision_enabled_t, bool> >> |
|
strong |
| KDL::Frame tesseract_scene_graph::convert | ( | const Eigen::Isometry3d & | transform | ) |
Convert Eigen::Isometry3d to KDL::Frame.
| transform | Input Eigen transform (Isometry3d) |
Definition at line 83 of file kdl_parser.cpp.
| KDL::Jacobian tesseract_scene_graph::convert | ( | const Eigen::MatrixXd & | jacobian | ) |
Convert Eigen::Matrix to KDL::Jacobian.
| jacobian | Input Eigen MatrixXd |
Definition at line 141 of file kdl_parser.cpp.
| KDL::Vector tesseract_scene_graph::convert | ( | const Eigen::Vector3d & | vector | ) |
Convert Eigen::Vector3d to KDL::Vector.
| vector | Input Eigen Vector3d |
Definition at line 135 of file kdl_parser.cpp.
| Eigen::Isometry3d tesseract_scene_graph::convert | ( | const KDL::Frame & | frame | ) |
Convert KDL::Frame to Eigen::Isometry3d.
| frame | Input KDL Frame |
Definition at line 106 of file kdl_parser.cpp.
| Eigen::MatrixXd tesseract_scene_graph::convert | ( | const KDL::Jacobian & | jacobian | ) |
Convert KDL::Jacobian to Eigen::Matrix.
| jacobian | Input KDL Jacobian |
Definition at line 139 of file kdl_parser.cpp.
| Eigen::MatrixXd tesseract_scene_graph::convert | ( | const KDL::Jacobian & | jacobian, |
| const std::vector< int > & | q_nrs | ||
| ) |
Convert a subset of KDL::Jacobian to Eigen::Matrix.
| jacobian | Input KDL Jacobian |
| q_nrs | Input the columns to use |
Definition at line 152 of file kdl_parser.cpp.
| Eigen::Vector3d tesseract_scene_graph::convert | ( | const KDL::Vector & | vector | ) |
Convert KDL::Vector to Eigen::Vector3d.
| transform | Input KDL Vector |
Definition at line 137 of file kdl_parser.cpp.
| KDL::RigidBodyInertia tesseract_scene_graph::convert | ( | const std::shared_ptr< const Inertial > & | inertial | ) |
Convert Tesseract Inertail to KDL Inertial.
| inertial |
Definition at line 200 of file kdl_parser.cpp.
| KDL::Joint tesseract_scene_graph::convert | ( | const std::shared_ptr< const Joint > & | joint | ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const JointCalibration & | calibration | ||
| ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const JointDynamics & | dynamics | ||
| ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const JointLimits & | limits | ||
| ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const JointMimic & | mimic | ||
| ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const JointSafety & | safety | ||
| ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const JointType & | type | ||
| ) |
| std::ostream & tesseract_scene_graph::operator<< | ( | std::ostream & | os, |
| const ShortestPath & | path | ||
| ) |
| KDLTreeData tesseract_scene_graph::parseSceneGraph | ( | const SceneGraph & | scene_graph | ) |
Convert a Tesseract SceneGraph into a KDL Tree.
| If | graph is not a tree |
| scene_graph | The Tesseract Scene Graph |
Definition at line 491 of file kdl_parser.cpp.
| KDLTreeData tesseract_scene_graph::parseSceneGraph | ( | const SceneGraph & | scene_graph, |
| const std::vector< std::string > & | joint_names, | ||
| const std::unordered_map< std::string, double > & | joint_values, | ||
| const tesseract_common::TransformMap & | floating_joint_values = {} |
||
| ) |
Convert a portion of a Tesseract SceneGraph into a KDL Tree.
This will create a new tree from multiple sub tree defined by the provided joint names The values are used to convert non fixed joints that are not listed in joint_names to a fixed joint. The first tree found a link is defined attaching world to the base link and all other trees are attached to this link by a fixed joint.
| If | graph is not a tree it will return false. |
| scene_graph | The Tesseract Scene Graph |
| joint_names | The active joint names |
| joint_values | The active joint values |
| floating_joint_values | The floating joint values |
Definition at line 531 of file kdl_parser.cpp.