Classes | Typedefs | Enumerations | Functions
tesseract_scene_graph Namespace Reference

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...
 

Typedef Documentation

◆ EdgeProperty

using tesseract_scene_graph::EdgeProperty = typedef boost::property<boost::edge_joint_t, std::shared_ptr<Joint>, boost::property<boost::edge_weight_t, double> >

EdgeProperty.

The edge_weight represents the distance between the two links

Definition at line 105 of file graph.h.

◆ Graph

using tesseract_scene_graph::Graph = typedef boost:: adjacency_list<boost::listS, boost::listS, boost::bidirectionalS, VertexProperty, EdgeProperty, GraphProperty>

Definition at line 108 of file graph.h.

◆ GraphProperty

using tesseract_scene_graph::GraphProperty = typedef boost::property<boost::graph_name_t, std::string, boost::property<boost::graph_root_t, std::string> >

Defines the boost graph property.

Definition at line 91 of file graph.h.

◆ UGraph

using tesseract_scene_graph::UGraph = typedef boost::adjacency_list<boost::listS, boost::listS, boost::undirectedS, VertexProperty, EdgeProperty, GraphProperty>

Definition at line 171 of file graph.cpp.

◆ VertexProperty

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> >>

Defines the boost graph vertex property.

Definition at line 97 of file graph.h.

Enumeration Type Documentation

◆ JointType

enum tesseract_scene_graph::JointType : std::uint8_t
strong
Enumerator
UNKNOWN 
REVOLUTE 
CONTINUOUS 
PRISMATIC 
FLOATING 
PLANAR 
FIXED 

Definition at line 261 of file joint.h.

Function Documentation

◆ convert() [1/9]

KDL::Frame tesseract_scene_graph::convert ( const Eigen::Isometry3d &  transform)

Convert Eigen::Isometry3d to KDL::Frame.

Parameters
transformInput Eigen transform (Isometry3d)
Returns
frame Output KDL Frame

Definition at line 83 of file kdl_parser.cpp.

◆ convert() [2/9]

KDL::Jacobian tesseract_scene_graph::convert ( const Eigen::MatrixXd &  jacobian)

Convert Eigen::Matrix to KDL::Jacobian.

Parameters
jacobianInput Eigen MatrixXd
Returns
KDL Jacobian

Definition at line 141 of file kdl_parser.cpp.

◆ convert() [3/9]

KDL::Vector tesseract_scene_graph::convert ( const Eigen::Vector3d &  vector)

Convert Eigen::Vector3d to KDL::Vector.

Parameters
vectorInput Eigen Vector3d
Returns
vector Output KDL Vector

Definition at line 135 of file kdl_parser.cpp.

◆ convert() [4/9]

Eigen::Isometry3d tesseract_scene_graph::convert ( const KDL::Frame &  frame)

Convert KDL::Frame to Eigen::Isometry3d.

Parameters
frameInput KDL Frame
Returns
Eigen transform (Isometry3d)

Definition at line 106 of file kdl_parser.cpp.

◆ convert() [5/9]

Eigen::MatrixXd tesseract_scene_graph::convert ( const KDL::Jacobian &  jacobian)

Convert KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
Returns
Eigen MatrixXd

Definition at line 139 of file kdl_parser.cpp.

◆ convert() [6/9]

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.

Parameters
jacobianInput KDL Jacobian
q_nrsInput the columns to use
Returns
Eigen MatrixXd

Definition at line 152 of file kdl_parser.cpp.

◆ convert() [7/9]

Eigen::Vector3d tesseract_scene_graph::convert ( const KDL::Vector &  vector)

Convert KDL::Vector to Eigen::Vector3d.

Parameters
transformInput KDL Vector
Returns
frame Output Eigen Vector3d

Definition at line 137 of file kdl_parser.cpp.

◆ convert() [8/9]

KDL::RigidBodyInertia tesseract_scene_graph::convert ( const std::shared_ptr< const Inertial > &  inertial)

Convert Tesseract Inertail to KDL Inertial.

Parameters
inertial
Returns

Definition at line 200 of file kdl_parser.cpp.

◆ convert() [9/9]

KDL::Joint tesseract_scene_graph::convert ( const std::shared_ptr< const Joint > &  joint)

Convert Tesseract Joint to KDL Joint.

Parameters
jointTesseract Joint
Returns
A KDL Joint

Definition at line 165 of file kdl_parser.cpp.

◆ operator<<() [1/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointCalibration calibration 
)

Definition at line 207 of file joint.cpp.

◆ operator<<() [2/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointDynamics dynamics 
)

Definition at line 67 of file joint.cpp.

◆ operator<<() [3/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointLimits limits 
)

Definition at line 117 of file joint.cpp.

◆ operator<<() [4/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointMimic mimic 
)

Definition at line 248 of file joint.cpp.

◆ operator<<() [5/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointSafety safety 
)

Definition at line 166 of file joint.cpp.

◆ operator<<() [6/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointType type 
)

Definition at line 342 of file joint.cpp.

◆ operator<<() [7/7]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const ShortestPath path 
)

Definition at line 1345 of file graph.cpp.

◆ parseSceneGraph() [1/2]

KDLTreeData tesseract_scene_graph::parseSceneGraph ( const SceneGraph scene_graph)

Convert a Tesseract SceneGraph into a KDL Tree.

Exceptions
Ifgraph is not a tree
Parameters
scene_graphThe Tesseract Scene Graph
Returns
Returns KDL tree data representation of the scene graph

Definition at line 491 of file kdl_parser.cpp.

◆ parseSceneGraph() [2/2]

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.

Exceptions
Ifgraph is not a tree it will return false.
Parameters
scene_graphThe Tesseract Scene Graph
joint_namesThe active joint names
joint_valuesThe active joint values
floating_joint_valuesThe floating joint values
Returns
Returns KDL tree representation of the sub scene graph

Definition at line 531 of file kdl_parser.cpp.



tesseract_scene_graph
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:49